aboutsummaryrefslogtreecommitdiff
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
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
-rw-r--r--src/modules/navigator/mission_block.cpp4
-rw-r--r--src/modules/navigator/navigator.h4
-rw-r--r--src/modules/navigator/navigator_main.cpp2
-rw-r--r--src/modules/navigator/navigator_params.c6
-rw-r--r--src/modules/navigator/rtl.cpp15
-rw-r--r--src/modules/navigator/rtl.h1
-rw-r--r--src/modules/navigator/rtl_params.c12
7 files changed, 15 insertions, 29 deletions
diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp
index 8ef7be449..4f177d76e 100644
--- a/src/modules/navigator/mission_block.cpp
+++ b/src/modules/navigator/mission_block.cpp
@@ -100,12 +100,12 @@ MissionBlock::is_mission_item_reached()
if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF && _navigator_priv->get_vstatus()->is_rotary_wing) {
/* require only altitude for takeoff for multicopter */
if (_navigator_priv->get_global_position()->alt >
- altitude_amsl - _navigator_priv->get_takeoff_acceptance_radius()) {
+ altitude_amsl - _navigator_priv->get_acceptance_radius()) {
_waypoint_position_reached = true;
}
} else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF) {
/* for takeoff mission items use the parameter for the takeoff acceptance radius */
- if (dist >= 0.0f && dist <= _navigator_priv->get_takeoff_acceptance_radius()) {
+ if (dist >= 0.0f && dist <= _navigator_priv->get_acceptance_radius()) {
_waypoint_position_reached = true;
}
} else {
diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h
index 4709f7196..184ecd365 100644
--- a/src/modules/navigator/navigator.h
+++ b/src/modules/navigator/navigator.h
@@ -115,7 +115,7 @@ public:
Geofence& get_geofence() { return _geofence; }
bool get_can_loiter_at_sp() { return _can_loiter_at_sp; }
float get_loiter_radius() { return _param_loiter_radius.get(); }
- float get_takeoff_acceptance_radius() { return _param_takeoff_acceptance_radius.get(); }
+ float get_acceptance_radius() { return _param_acceptance_radius.get(); }
int get_mavlink_fd() { return _mavlink_fd; }
private:
@@ -165,7 +165,7 @@ private:
bool _update_triplet; /**< flags if position SP triplet needs to be published */
control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */
- control::BlockParamFloat _param_takeoff_acceptance_radius; /**< acceptance for takeoff */
+ control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */
/**
* Retrieve global position
*/
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index e22c4d72d..546602741 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -123,7 +123,7 @@ Navigator::Navigator() :
_rtl(this, "RTL"),
_update_triplet(false),
_param_loiter_radius(this, "LOITER_RAD"),
- _param_takeoff_acceptance_radius(this, "TF_ACC_RAD")
+ _param_acceptance_radius(this, "ACC_RAD")
{
/* Create a list of our possible navigation types */
_navigation_mode_array[0] = &_mission;
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index ca31adecc..084afe340 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -55,12 +55,12 @@
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
/**
- * Takeoff Acceptance Radius (FW only)
+ * Acceptance Radius
*
- * Acceptance radius for fixedwing.
+ * Default acceptance radius, overridden by acceptance radius of waypoint if set.
*
* @unit meters
* @min 1.0
* @group Mission
*/
-PARAM_DEFINE_FLOAT(NAV_TF_ACC_RAD, 25.0f);
+PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 25.0f);
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;
diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h
index c4286b391..90299c3fa 100644
--- a/src/modules/navigator/rtl.h
+++ b/src/modules/navigator/rtl.h
@@ -105,7 +105,6 @@ private:
control::BlockParamFloat _param_return_alt;
control::BlockParamFloat _param_descend_alt;
control::BlockParamFloat _param_land_delay;
- control::BlockParamFloat _param_acceptance_radius;
};
#endif
diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c
index 63724f461..bfe6ce7e1 100644
--- a/src/modules/navigator/rtl_params.c
+++ b/src/modules/navigator/rtl_params.c
@@ -96,15 +96,3 @@ PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 20);
* @group RTL
*/
PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, -1.0f);
-
-/**
- * RTL acceptance radius
- *
- * Acceptance radius for waypoints set for RTL
- *
- * @unit meters
- * @min 1
- * @max
- * @group RTL
- */
-PARAM_DEFINE_FLOAT(RTL_ACCEPT_RAD, 25.0f);