aboutsummaryrefslogtreecommitdiff
path: root/src/modules/navigator/rtl.cpp
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-06-27 11:09:49 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-06-27 11:09:49 +0200
commit52eb49ba0bd1ea5a05845350f1b3c46f0b059a39 (patch)
treec2beb161dc4a8a439b6721b6e0903242c833e706 /src/modules/navigator/rtl.cpp
parent1bae18377a444279f91b75281ffde5da70cc6086 (diff)
downloadpx4-firmware-52eb49ba0bd1ea5a05845350f1b3c46f0b059a39.tar.gz
px4-firmware-52eb49ba0bd1ea5a05845350f1b3c46f0b059a39.tar.bz2
px4-firmware-52eb49ba0bd1ea5a05845350f1b3c46f0b059a39.zip
navigator: use common "acceptance radius" parameter for all modes
Diffstat (limited to 'src/modules/navigator/rtl.cpp')
-rw-r--r--src/modules/navigator/rtl.cpp15
1 files changed, 7 insertions, 8 deletions
diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp
index b7961a260..af2ff308c 100644
--- a/src/modules/navigator/rtl.cpp
+++ b/src/modules/navigator/rtl.cpp
@@ -61,8 +61,7 @@ RTL::RTL(Navigator *navigator, const char *name) :
_rtl_state(RTL_STATE_NONE),
_param_return_alt(this, "RETURN_ALT"),
_param_descend_alt(this, "DESCEND_ALT"),
- _param_land_delay(this, "LAND_DELAY"),
- _param_acceptance_radius(this, "ACCEPT_RAD")
+ _param_land_delay(this, "LAND_DELAY")
{
/* load initial params */
updateParams();
@@ -147,7 +146,7 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
_mission_item.loiter_radius = _navigator->get_loiter_radius();
_mission_item.loiter_direction = 1;
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
- _mission_item.acceptance_radius = _param_acceptance_radius.get();
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
_mission_item.time_inside = 0.0f;
_mission_item.pitch_min = 0.0f;
_mission_item.autocontinue = true;
@@ -178,7 +177,7 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
_mission_item.loiter_radius = _navigator->get_loiter_radius();
_mission_item.loiter_direction = 1;
_mission_item.nav_cmd = NAV_CMD_WAYPOINT;
- _mission_item.acceptance_radius = _param_acceptance_radius.get();
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
_mission_item.time_inside = 0.0f;
_mission_item.pitch_min = 0.0f;
_mission_item.autocontinue = true;
@@ -198,7 +197,7 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
_mission_item.loiter_radius = _navigator->get_loiter_radius();
_mission_item.loiter_direction = 1;
_mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
- _mission_item.acceptance_radius = _param_acceptance_radius.get();
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
_mission_item.time_inside = 0.0f;
_mission_item.pitch_min = 0.0f;
_mission_item.autocontinue = false;
@@ -220,7 +219,7 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
_mission_item.loiter_radius = _navigator->get_loiter_radius();
_mission_item.loiter_direction = 1;
_mission_item.nav_cmd = autoland ? NAV_CMD_LOITER_TIME_LIMIT : NAV_CMD_LOITER_UNLIMITED;
- _mission_item.acceptance_radius = _param_acceptance_radius.get();
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
_mission_item.time_inside = _param_land_delay.get() < 0.0f ? 0.0f : _param_land_delay.get();
_mission_item.pitch_min = 0.0f;
_mission_item.autocontinue = autoland;
@@ -246,7 +245,7 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
_mission_item.loiter_radius = _navigator->get_loiter_radius();
_mission_item.loiter_direction = 1;
_mission_item.nav_cmd = NAV_CMD_LAND;
- _mission_item.acceptance_radius = _param_acceptance_radius.get();
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
_mission_item.time_inside = 0.0f;
_mission_item.pitch_min = 0.0f;
_mission_item.autocontinue = true;
@@ -265,7 +264,7 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
_mission_item.loiter_radius = _navigator->get_loiter_radius();
_mission_item.loiter_direction = 1;
_mission_item.nav_cmd = NAV_CMD_IDLE;
- _mission_item.acceptance_radius = _param_acceptance_radius.get();
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
_mission_item.time_inside = 0.0f;
_mission_item.pitch_min = 0.0f;
_mission_item.autocontinue = true;