mirror of https://github.com/ArduPilot/ardupilot
Plane: Move loiter_radius to vehicle
This commit is contained in:
parent
302e80d72c
commit
2326eee9a0
|
@ -292,7 +292,7 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
// @Range: -32767 32767
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS_DEFAULT),
|
||||
ASCALAR(loiter_radius, "WP_LOITER_RAD", LOITER_RADIUS_DEFAULT),
|
||||
|
||||
// @Param: RTL_RADIUS
|
||||
// @DisplayName: RTL loiter radius
|
||||
|
|
|
@ -401,7 +401,6 @@ public:
|
|||
AP_Int8 waypoint_mode;
|
||||
AP_Int16 waypoint_radius;
|
||||
AP_Int16 waypoint_max_radius;
|
||||
AP_Int16 loiter_radius;
|
||||
AP_Int16 rtl_radius;
|
||||
|
||||
#if GEOFENCE_ENABLED == ENABLED
|
||||
|
|
|
@ -70,7 +70,7 @@ void Plane::set_next_WP(const struct Location &loc)
|
|||
|
||||
void Plane::set_guided_WP(void)
|
||||
{
|
||||
if (g.loiter_radius < 0 || guided_WP_loc.flags.loiter_ccw) {
|
||||
if (aparm.loiter_radius < 0 || guided_WP_loc.flags.loiter_ccw) {
|
||||
loiter.direction = -1;
|
||||
} else {
|
||||
loiter.direction = 1;
|
||||
|
|
|
@ -337,7 +337,7 @@ void Plane::do_RTL(int32_t rtl_altitude)
|
|||
setup_terrain_target_alt(next_WP_loc);
|
||||
set_target_altitude_location(next_WP_loc);
|
||||
|
||||
if (g.loiter_radius < 0) {
|
||||
if (aparm.loiter_radius < 0) {
|
||||
loiter.direction = -1;
|
||||
} else {
|
||||
loiter.direction = 1;
|
||||
|
@ -653,7 +653,7 @@ bool Plane::verify_loiter_unlim()
|
|||
bool Plane::verify_loiter_time()
|
||||
{
|
||||
bool result = false;
|
||||
// mission radius is always g.loiter_radius
|
||||
// mission radius is always aparm.loiter_radius
|
||||
update_loiter(0);
|
||||
|
||||
if (loiter.start_time_ms == 0) {
|
||||
|
@ -861,7 +861,7 @@ bool Plane::verify_within_distance()
|
|||
|
||||
void Plane::do_loiter_at_location()
|
||||
{
|
||||
if (g.loiter_radius < 0) {
|
||||
if (aparm.loiter_radius < 0) {
|
||||
loiter.direction = -1;
|
||||
} else {
|
||||
loiter.direction = 1;
|
||||
|
@ -1031,7 +1031,7 @@ bool Plane::verify_loiter_heading(bool init)
|
|||
return true;
|
||||
}
|
||||
|
||||
if (get_distance(next_WP_loc, next_nav_cmd.content.location) < labs(g.loiter_radius)) {
|
||||
if (get_distance(next_WP_loc, next_nav_cmd.content.location) < labs(aparm.loiter_radius)) {
|
||||
/* Whenever next waypoint is within the loiter radius,
|
||||
maintaining loiter would prevent us from ever pointing toward the next waypoint.
|
||||
Hence break out of loiter immediately
|
||||
|
|
|
@ -143,11 +143,11 @@ void Plane::update_loiter(uint16_t radius)
|
|||
{
|
||||
if (radius <= 1) {
|
||||
// if radius is <=1 then use the general loiter radius. if it's small, use default
|
||||
radius = (abs(g.loiter_radius) <= 1) ? LOITER_RADIUS_DEFAULT : abs(g.loiter_radius);
|
||||
radius = (abs(aparm.loiter_radius) <= 1) ? LOITER_RADIUS_DEFAULT : abs(aparm.loiter_radius);
|
||||
if (next_WP_loc.flags.loiter_ccw == 1) {
|
||||
loiter.direction = -1;
|
||||
} else {
|
||||
loiter.direction = (g.loiter_radius < 0) ? -1 : 1;
|
||||
loiter.direction = (aparm.loiter_radius < 0) ? -1 : 1;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue