|
|
@ -3,12 +3,6 @@ |
|
|
|
|
|
|
|
|
|
|
|
void ModeAcro::update() |
|
|
|
void ModeAcro::update() |
|
|
|
{ |
|
|
|
{ |
|
|
|
float desired_steering, desired_throttle; |
|
|
|
|
|
|
|
get_pilot_desired_steering_and_throttle(desired_steering, desired_throttle); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// convert pilot throttle input to desired speed (up to twice the cruise speed)
|
|
|
|
|
|
|
|
float target_speed = desired_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// get speed forward
|
|
|
|
// get speed forward
|
|
|
|
float speed; |
|
|
|
float speed; |
|
|
|
if (!attitude_control.get_forward_speed(speed)) { |
|
|
|
if (!attitude_control.get_forward_speed(speed)) { |
|
|
@ -18,23 +12,31 @@ void ModeAcro::update() |
|
|
|
return; |
|
|
|
return; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// convert pilot stick input into desired steering and throttle
|
|
|
|
|
|
|
|
float desired_steering, desired_throttle; |
|
|
|
|
|
|
|
get_pilot_desired_steering_and_throttle(desired_steering, desired_throttle); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// convert pilot throttle input to desired speed (up to twice the cruise speed)
|
|
|
|
|
|
|
|
float target_speed = desired_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// convert pilot steering input to desired turn rate in radians/sec
|
|
|
|
|
|
|
|
float target_turn_rate = (desired_steering / 4500.0f) * radians(g2.acro_turn_rate); |
|
|
|
|
|
|
|
|
|
|
|
// determine if pilot is requesting pivot turn
|
|
|
|
// determine if pilot is requesting pivot turn
|
|
|
|
bool is_pivot_turning = g2.motors.have_skid_steering() && is_zero(target_speed) && (!is_zero(desired_steering)); |
|
|
|
bool is_pivot_turning = g2.motors.have_skid_steering() && is_zero(target_speed) && (!is_zero(desired_steering)); |
|
|
|
|
|
|
|
|
|
|
|
// convert steering request to turn rate in radians/sec
|
|
|
|
// stop vehicle if target speed is zero and not pivot turning
|
|
|
|
float turn_rate = (desired_steering / 4500.0f) * radians(g2.acro_turn_rate); |
|
|
|
if (is_zero(target_speed) && !is_pivot_turning) { |
|
|
|
|
|
|
|
stop_vehicle(); |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// set reverse flag backing up
|
|
|
|
// set reverse flag backing up
|
|
|
|
bool reversed = is_negative(target_speed); |
|
|
|
bool reversed = is_negative(target_speed); |
|
|
|
rover.set_reverse(reversed); |
|
|
|
rover.set_reverse(reversed); |
|
|
|
|
|
|
|
|
|
|
|
// run speed to throttle output controller
|
|
|
|
// run steering turn rate controller and throttle controller
|
|
|
|
if (is_zero(target_speed) && !is_pivot_turning) { |
|
|
|
float steering_out = attitude_control.get_steering_out_rate(target_turn_rate, g2.motors.have_skid_steering(), g2.motors.limit.steer_left, g2.motors.limit.steer_right, reversed); |
|
|
|
stop_vehicle(); |
|
|
|
g2.motors.set_steering(steering_out * 4500.0f); |
|
|
|
} else { |
|
|
|
calc_throttle(target_speed, false); |
|
|
|
// run steering turn rate controller and throttle controller
|
|
|
|
|
|
|
|
float steering_out = attitude_control.get_steering_out_rate(turn_rate, g2.motors.have_skid_steering(), g2.motors.limit.steer_left, g2.motors.limit.steer_right, reversed); |
|
|
|
|
|
|
|
g2.motors.set_steering(steering_out * 4500.0f); |
|
|
|
|
|
|
|
calc_throttle(target_speed, false); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|