Browse Source

Rover: Added reversing loiter_type parameter

zr-v5.1
sahith22 5 years ago committed by Randy Mackay
parent
commit
e7c2528654
  1. 2
      APMrover2/Parameters.cpp
  2. 2
      APMrover2/mode_loiter.cpp

2
APMrover2/Parameters.cpp

@ -511,7 +511,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { @@ -511,7 +511,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: LOIT_TYPE
// @DisplayName: Loiter type
// @Description: Loiter behaviour when moving to the target point
// @Values: 0:Forward or reverse to target point,1:Always face bow towards target point
// @Values: 0:Forward or reverse to target point,1:Always face bow towards target point,2:Always face stern towards target point
// @User: Standard
AP_GROUPINFO("LOIT_TYPE", 25, ParametersG2, loit_type, 0),

2
APMrover2/mode_loiter.cpp

@ -44,7 +44,7 @@ void ModeLoiter::update() @@ -44,7 +44,7 @@ void ModeLoiter::update()
_desired_yaw_cd = rover.current_loc.get_bearing_to(_destination);
float yaw_error_cd = wrap_180_cd(_desired_yaw_cd - ahrs.yaw_sensor);
// 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);
yaw_error_cd = wrap_180_cd(_desired_yaw_cd - ahrs.yaw_sensor);
_desired_speed = -_desired_speed;

Loading…
Cancel
Save