Skip to content

Commit

Permalink
AP_MotorsHeli: Whitespace and comments fixups
Browse files Browse the repository at this point in the history
  • Loading branch information
MattKear committed Mar 24, 2024
1 parent 523ecd2 commit d39314a
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 2 deletions.
3 changes: 3 additions & 0 deletions libraries/AP_Motors/AP_MotorsHeli.h
Original file line number Diff line number Diff line change
Expand Up @@ -286,8 +286,11 @@ class AP_MotorsHeli : public AP_Motors {
AP_Float _cyclic_angle_max_deg; // The blade pitch angle angle contribution in degrees of the cyclic output contribution

// internal variables
float _collective_zero_thrust_pct; // collective zero thrust parameter value converted to 0 ~ 1 range
float _collective_land_min_pct; // collective land min parameter value converted to 0 ~ 1 range
float _coll_ang_deg[AP_MOTORS_HELI_MAX_INDEPENDENT_COLL]; // collective blade pitch angle contributions for each swashplate after mixing
float _cyclic_ang_deg[AP_MOTORS_HELI_MAX_INDEPENDENT_CYCLIC]; // cyclic blade pitch angle contributions for each swashplate after mixing
uint8_t _servo_test_cycle_counter = 0; // number of test cycles left to run after bootup

motor_frame_type _frame_type;
motor_frame_class _frame_class;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsHeli_Dual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -422,7 +422,7 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c
pitch_out = _cyclic_max/4500.0f;
limit.pitch = true;
}
} else {
} else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM
if (roll_out < -_cyclic_max/4500.0f) {
roll_out = -_cyclic_max/4500.0f;
limit.roll = true;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsHeli_Single.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -437,7 +437,7 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
float collective_scalar = ((float)(_collective_max-_collective_min))*0.001f;
float collective_out_scaled = collective_out * collective_scalar + (_collective_min - 1000)*0.001f;

// Caculate servo positions from swashplate library
// Calculate servo positions from swashplate library
_swashplate.calculate(roll_out, pitch_out, collective_out_scaled);

// update the yaw rate using the tail rotor/servo
Expand Down

0 comments on commit d39314a

Please sign in to comment.