mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Motors: init members in constructor
Also add f to end of float constants
This commit is contained in:
parent
8f275ca2c4
commit
71e4bccecb
@ -105,10 +105,17 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
|
||||
|
||||
// Constructor
|
||||
AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
||||
_roll_control_input(0.0f),
|
||||
_pitch_control_input(0.0f),
|
||||
_throttle_control_input(0.0f),
|
||||
_yaw_control_input(0.0f),
|
||||
_throttle_pwm_scalar(1.0f),
|
||||
_loop_rate(loop_rate),
|
||||
_speed_hz(speed_hz),
|
||||
_min_throttle(AP_MOTORS_DEFAULT_MIN_THROTTLE),
|
||||
_max_throttle(AP_MOTORS_DEFAULT_MAX_THROTTLE),
|
||||
_throttle_radio_min(1100),
|
||||
_throttle_radio_max(1900),
|
||||
_hover_out(AP_MOTORS_DEFAULT_MID_THROTTLE),
|
||||
_spin_when_armed_ramped(0),
|
||||
_throttle_thr_mix(AP_MOTORS_THR_LOW_CMP_DEFAULT),
|
||||
|
@ -254,9 +254,9 @@ protected:
|
||||
// RPY channels typically +/-45 degrees servo travel between +/-400 PWM
|
||||
// Throttle channel typically 0-1000 range converts to 1100-1900 PWM for final output signal to motors
|
||||
// ToDo: this should all be handled as floats +/- 1.0 instead of PWM and fake angle ranges
|
||||
int16_t calc_roll_pwm() { return (_roll_control_input / 11.25);}
|
||||
int16_t calc_pitch_pwm() { return (_pitch_control_input / 11.25);}
|
||||
int16_t calc_yaw_pwm() { return (_yaw_control_input / 11.25);}
|
||||
int16_t calc_roll_pwm() { return (_roll_control_input / 11.25f);}
|
||||
int16_t calc_pitch_pwm() { return (_pitch_control_input / 11.25f);}
|
||||
int16_t calc_yaw_pwm() { return (_yaw_control_input / 11.25f);}
|
||||
int16_t calc_throttle_radio_output() { return (_throttle_control_input * _throttle_pwm_scalar) + _throttle_radio_min;}
|
||||
|
||||
// flag bitmask
|
||||
|
Loading…
Reference in New Issue
Block a user