mirror of https://github.com/ArduPilot/ardupilot
Rover: enable avoidance in auto, RTL, smartRTL
This commit is contained in:
parent
66a2c10203
commit
17af4c8933
|
@ -53,7 +53,7 @@ void ModeAuto::update()
|
|||
if (!_reached_destination || (rover.is_boat() && !near_wp)) {
|
||||
// continue driving towards destination
|
||||
calc_steering_to_waypoint(_reached_destination ? rover.current_loc : _origin, _destination, _reversed);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, false);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, true);
|
||||
} else {
|
||||
// we have reached the destination so stop
|
||||
stop_vehicle();
|
||||
|
@ -66,7 +66,7 @@ void ModeAuto::update()
|
|||
if (!_reached_heading) {
|
||||
// run steering and throttle controllers
|
||||
calc_steering_to_heading(_desired_yaw_cd);
|
||||
calc_throttle(_desired_speed, true, false);
|
||||
calc_throttle(_desired_speed, true, true);
|
||||
// check if we have reached within 5 degrees of target
|
||||
_reached_heading = (fabsf(_desired_yaw_cd - ahrs.yaw_sensor) < 500);
|
||||
} else {
|
||||
|
|
|
@ -37,7 +37,7 @@ void ModeRTL::update()
|
|||
if (!_reached_destination || (rover.is_boat() && !near_wp)) {
|
||||
// continue driving towards destination
|
||||
calc_steering_to_waypoint(_reached_destination ? rover.current_loc :_origin, _destination, _reversed);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, false);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, true);
|
||||
} else {
|
||||
// we've reached destination so stop
|
||||
stop_vehicle();
|
||||
|
|
|
@ -65,7 +65,7 @@ void ModeSmartRTL::update()
|
|||
}
|
||||
// continue driving towards destination
|
||||
calc_steering_to_waypoint(_origin, _destination, _reversed);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, false);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, true);
|
||||
break;
|
||||
|
||||
case SmartRTL_StopAtHome:
|
||||
|
@ -74,7 +74,7 @@ void ModeSmartRTL::update()
|
|||
if (rover.is_boat()) {
|
||||
// boats attempt to hold position at home
|
||||
calc_steering_to_waypoint(rover.current_loc, _destination, _reversed);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, false);
|
||||
calc_throttle(calc_reduced_speed_for_turn_or_distance(_reversed ? -_desired_speed : _desired_speed), true, true);
|
||||
} else {
|
||||
// rovers stop
|
||||
stop_vehicle();
|
||||
|
|
Loading…
Reference in New Issue