AP_Motors: minor format fixes

This commit is contained in:
Randy Mackay 2019-01-21 20:07:21 +09:00
parent 3d3f06cacb
commit e2bd502b83
2 changed files with 9 additions and 9 deletions

View File

@ -193,7 +193,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
// @Increment: 0.001 // @Increment: 0.001
// @User: Advanced // @User: Advanced
AP_GROUPINFO("SLEW_UP_TIME", 40, AP_MotorsMulticopter, _slew_up_time, AP_MOTORS_SLEW_TIME_DEFAULT), AP_GROUPINFO("SLEW_UP_TIME", 40, AP_MotorsMulticopter, _slew_up_time, AP_MOTORS_SLEW_TIME_DEFAULT),
// @Param: SLEW_DN_TIME // @Param: SLEW_DN_TIME
// @DisplayName: Output slew time for decreasing throttle // @DisplayName: Output slew time for decreasing throttle
// @Description: Time in seconds to slew output from full to zero. For medium size copter such as a Solo, a value of 0.275 is a good starting point. This is used to limit the rate at which output can change. Range is constrained between 0 and 0.5. // @Description: Time in seconds to slew output from full to zero. For medium size copter such as a Solo, a value of 0.275 is a good starting point. This is used to limit the rate at which output can change. Range is constrained between 0 and 0.5.
@ -416,17 +416,17 @@ void AP_MotorsMulticopter::set_actuator_with_slew(float& actuator_output, float
MOT_SLEW_UP_TIME and MOT_SLEW_DN_TIME are constrained to 0.0~0.5 for sanity. MOT_SLEW_UP_TIME and MOT_SLEW_DN_TIME are constrained to 0.0~0.5 for sanity.
If spool mode is shutdown, no slew limit is applied to allow immediate disarming of motors. If spool mode is shutdown, no slew limit is applied to allow immediate disarming of motors.
*/ */
// Output limits with no slew time applied // Output limits with no slew time applied
float output_slew_limit_up = 1.0f; float output_slew_limit_up = 1.0f;
float output_slew_limit_dn = 0.0f; float output_slew_limit_dn = 0.0f;
// If MOT_SLEW_UP_TIME is set, calculate the highest allowed new output value, constrained 0.0~1.0 // If MOT_SLEW_UP_TIME is set, calculate the highest allowed new output value, constrained 0.0~1.0
if (is_positive(_slew_up_time)) { if (is_positive(_slew_up_time)) {
float output_delta_up_max = 1.0f/(constrain_float(_slew_up_time,0.0f,0.5f) * _loop_rate); float output_delta_up_max = 1.0f/(constrain_float(_slew_up_time,0.0f,0.5f) * _loop_rate);
output_slew_limit_up = constrain_float(actuator_output + output_delta_up_max, 0.0f, 1.0f); output_slew_limit_up = constrain_float(actuator_output + output_delta_up_max, 0.0f, 1.0f);
} }
// If MOT_SLEW_DN_TIME is set, calculate the lowest allowed new output value, constrained 0.0~1.0 // If MOT_SLEW_DN_TIME is set, calculate the lowest allowed new output value, constrained 0.0~1.0
if (is_positive(_slew_dn_time)) { if (is_positive(_slew_dn_time)) {
float output_delta_dn_max = 1.0f/(constrain_float(_slew_dn_time,0.0f,0.5f) * _loop_rate); float output_delta_dn_max = 1.0f/(constrain_float(_slew_dn_time,0.0f,0.5f) * _loop_rate);

View File

@ -91,7 +91,7 @@ public:
// var_info for holding Parameter information // var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];
protected: protected:
// run spool logic // run spool logic
@ -117,10 +117,10 @@ protected:
// convert actuator output (0~1) range to pwm range // convert actuator output (0~1) range to pwm range
int16_t output_to_pwm(float _actuator_output); int16_t output_to_pwm(float _actuator_output);
// converts desired thrust to linearized actuator output in a range of 0~1 // converts desired thrust to linearized actuator output in a range of 0~1
float thrust_to_actuator(float thrust_in); float thrust_to_actuator(float thrust_in);
// adds slew rate limiting to actuator output if MOT_SLEW_TIME > 0 and not shutdown // adds slew rate limiting to actuator output if MOT_SLEW_TIME > 0 and not shutdown
void set_actuator_with_slew(float& actuator_output, float input); void set_actuator_with_slew(float& actuator_output, float input);
@ -170,7 +170,7 @@ protected:
// scaling for booster motor throttle // scaling for booster motor throttle
AP_Float _boost_scale; AP_Float _boost_scale;
// motor output variables // motor output variables
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]; // true if motor is enabled bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]; // true if motor is enabled
int16_t _throttle_radio_min; // minimum PWM from RC input's throttle channel (i.e. minimum PWM input from receiver, RC3_MIN) int16_t _throttle_radio_min; // minimum PWM from RC input's throttle channel (i.e. minimum PWM input from receiver, RC3_MIN)
@ -189,7 +189,7 @@ protected:
// vehicle supplied callback for thrust compensation. Used for tiltrotors and tiltwings // vehicle supplied callback for thrust compensation. Used for tiltrotors and tiltwings
thrust_compensation_fn_t _thrust_compensation_callback; thrust_compensation_fn_t _thrust_compensation_callback;
// array of motor output values // array of motor output values
float _actuator[AP_MOTORS_MAX_NUM_MOTORS]; float _actuator[AP_MOTORS_MAX_NUM_MOTORS];
}; };