mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
Plane: allow for negative WP_LOITER_RAD for conter-clockwise loiter
this follows the same convention as missions
This commit is contained in:
parent
d01d754ba8
commit
994d8e354a
@ -1301,9 +1301,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
case MAV_CMD_NAV_LOITER_TIME:
|
case MAV_CMD_NAV_LOITER_TIME:
|
||||||
case MAV_CMD_NAV_LOITER_TURNS:
|
case MAV_CMD_NAV_LOITER_TURNS:
|
||||||
if (tell_command.options & MASK_OPTIONS_LOITER_DIRECTION) {
|
if (tell_command.options & MASK_OPTIONS_LOITER_DIRECTION) {
|
||||||
param3 = -g.loiter_radius;
|
param3 = -abs(g.loiter_radius);
|
||||||
} else {
|
} else {
|
||||||
param3 = g.loiter_radius;
|
param3 = abs(g.loiter_radius);
|
||||||
}
|
}
|
||||||
case MAV_CMD_NAV_TAKEOFF:
|
case MAV_CMD_NAV_TAKEOFF:
|
||||||
case MAV_CMD_DO_SET_HOME:
|
case MAV_CMD_DO_SET_HOME:
|
||||||
@ -1312,9 +1312,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
|
|
||||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||||
if (tell_command.options & MASK_OPTIONS_LOITER_DIRECTION) {
|
if (tell_command.options & MASK_OPTIONS_LOITER_DIRECTION) {
|
||||||
param3 = -g.loiter_radius;;
|
param3 = -abs(g.loiter_radius);
|
||||||
} else {
|
} else {
|
||||||
param3 = g.loiter_radius;
|
param3 = abs(g.loiter_radius);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MAV_CMD_CONDITION_CHANGE_ALT:
|
case MAV_CMD_CONDITION_CHANGE_ALT:
|
||||||
|
@ -184,7 +184,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
|
|
||||||
// @Param: WP_LOITER_RAD
|
// @Param: WP_LOITER_RAD
|
||||||
// @DisplayName: Waypoint Loiter Radius
|
// @DisplayName: Waypoint Loiter Radius
|
||||||
// @Description: Defines the distance from the waypoint center, the plane will maintain during a loiter
|
// @Description: Defines the distance from the waypoint center, the plane will maintain during a loiter. If you set this value to a negative number then the default loiter direction will be counter-clockwise instead of clockwise.
|
||||||
// @Units: Meters
|
// @Units: Meters
|
||||||
// @Range: 1 32767
|
// @Range: 1 32767
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
|
@ -230,7 +230,12 @@ static void do_RTL(void)
|
|||||||
control_mode = RTL;
|
control_mode = RTL;
|
||||||
crash_timer = 0;
|
crash_timer = 0;
|
||||||
next_WP = home;
|
next_WP = home;
|
||||||
loiter_direction = 1;
|
|
||||||
|
if (g.loiter_radius < 0) {
|
||||||
|
loiter_direction = -1;
|
||||||
|
} else {
|
||||||
|
loiter_direction = 1;
|
||||||
|
}
|
||||||
|
|
||||||
// Altitude to hold over home
|
// Altitude to hold over home
|
||||||
// Set by configuration tool
|
// Set by configuration tool
|
||||||
@ -268,7 +273,7 @@ static void loiter_set_direction_wp(const struct Location *nav_command)
|
|||||||
if (nav_command->options & MASK_OPTIONS_LOITER_DIRECTION) {
|
if (nav_command->options & MASK_OPTIONS_LOITER_DIRECTION) {
|
||||||
loiter_direction = -1;
|
loiter_direction = -1;
|
||||||
} else {
|
} else {
|
||||||
loiter_direction=1;
|
loiter_direction = 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -507,7 +512,11 @@ static bool verify_within_distance()
|
|||||||
|
|
||||||
static void do_loiter_at_location()
|
static void do_loiter_at_location()
|
||||||
{
|
{
|
||||||
loiter_direction = 1;
|
if (g.loiter_radius < 0) {
|
||||||
|
loiter_direction = -1;
|
||||||
|
} else {
|
||||||
|
loiter_direction = 1;
|
||||||
|
}
|
||||||
next_WP = current_loc;
|
next_WP = current_loc;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -142,6 +142,6 @@ static void calc_altitude_error()
|
|||||||
|
|
||||||
static void update_loiter()
|
static void update_loiter()
|
||||||
{
|
{
|
||||||
nav_controller->update_loiter(next_WP, g.loiter_radius, loiter_direction);
|
nav_controller->update_loiter(next_WP, abs(g.loiter_radius), loiter_direction);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user