Browse Source

Plane: pass rc_speed to motor backend constructors

this sets the right speed as early as possible
master
Andrew Tridgell 7 years ago
parent
commit
16c7ab81dc
  1. 8
      ArduPlane/quadplane.cpp

8
ArduPlane/quadplane.cpp

@ -526,16 +526,16 @@ bool QuadPlane::setup(void)
switch (motor_class) { switch (motor_class) {
case AP_Motors::MOTOR_FRAME_TRI: case AP_Motors::MOTOR_FRAME_TRI:
motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz()); motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz(), rc_speed);
motors_var_info = AP_MotorsTri::var_info; motors_var_info = AP_MotorsTri::var_info;
break; break;
case AP_Motors::MOTOR_FRAME_TAILSITTER: case AP_Motors::MOTOR_FRAME_TAILSITTER:
motors = new AP_MotorsTailsitter(plane.scheduler.get_loop_rate_hz()); motors = new AP_MotorsTailsitter(plane.scheduler.get_loop_rate_hz(), rc_speed);
motors_var_info = AP_MotorsTailsitter::var_info; motors_var_info = AP_MotorsTailsitter::var_info;
rotation = ROTATION_PITCH_90; rotation = ROTATION_PITCH_90;
break; break;
default: default:
motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz()); motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz(), rc_speed);
motors_var_info = AP_MotorsMatrix::var_info; motors_var_info = AP_MotorsMatrix::var_info;
break; break;
} }
@ -1170,7 +1170,7 @@ bool QuadPlane::assistance_needed(float aspeed)
return false; return false;
} }
uint32_t max_angle_cd = 100U*assist_angle; int32_t max_angle_cd = 100U*assist_angle;
if ((labs(ahrs.roll_sensor - plane.nav_roll_cd) < max_angle_cd && if ((labs(ahrs.roll_sensor - plane.nav_roll_cd) < max_angle_cd &&
labs(ahrs.pitch_sensor - plane.nav_pitch_cd) < max_angle_cd)) { labs(ahrs.pitch_sensor - plane.nav_pitch_cd) < max_angle_cd)) {
// not beyond angle error // not beyond angle error

Loading…
Cancel
Save