|
|
@ -44,7 +44,7 @@ void ModeLoiter::update() |
|
|
|
_desired_yaw_cd = rover.current_loc.get_bearing_to(_destination); |
|
|
|
_desired_yaw_cd = rover.current_loc.get_bearing_to(_destination); |
|
|
|
float yaw_error_cd = wrap_180_cd(_desired_yaw_cd - ahrs.yaw_sensor); |
|
|
|
float yaw_error_cd = wrap_180_cd(_desired_yaw_cd - ahrs.yaw_sensor); |
|
|
|
// if destination is behind vehicle, reverse towards it
|
|
|
|
// if destination is behind vehicle, reverse towards it
|
|
|
|
if (fabsf(yaw_error_cd) > 9000 && g2.loit_type == 0) { |
|
|
|
if ((fabsf(yaw_error_cd) > 9000 && g2.loit_type == 0) || g2.loit_type == 2){ |
|
|
|
_desired_yaw_cd = wrap_180_cd(_desired_yaw_cd + 18000); |
|
|
|
_desired_yaw_cd = wrap_180_cd(_desired_yaw_cd + 18000); |
|
|
|
yaw_error_cd = wrap_180_cd(_desired_yaw_cd - ahrs.yaw_sensor); |
|
|
|
yaw_error_cd = wrap_180_cd(_desired_yaw_cd - ahrs.yaw_sensor); |
|
|
|
_desired_speed = -_desired_speed; |
|
|
|
_desired_speed = -_desired_speed; |
|
|
|