aboutsummaryrefslogtreecommitdiff
path: root/src/modules/navigator/gpsfailure.cpp
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-08-22 00:40:45 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-08-22 00:40:45 +0200
commit752a0a562564ccc6f7d49ceebe810de7e6a6d358 (patch)
tree4cbf58d1fbda81009b289b641882eff6895a5045 /src/modules/navigator/gpsfailure.cpp
parent1a14ff250e5a2ead69576762fd5b7f176c4b6fac (diff)
downloadpx4-firmware-752a0a562564ccc6f7d49ceebe810de7e6a6d358.tar.gz
px4-firmware-752a0a562564ccc6f7d49ceebe810de7e6a6d358.tar.bz2
px4-firmware-752a0a562564ccc6f7d49ceebe810de7e6a6d358.zip
add obc gps failure mode
Diffstat (limited to 'src/modules/navigator/gpsfailure.cpp')
-rw-r--r--src/modules/navigator/gpsfailure.cpp95
1 files changed, 51 insertions, 44 deletions
diff --git a/src/modules/navigator/gpsfailure.cpp b/src/modules/navigator/gpsfailure.cpp
index 4c526b76e..02e766ffb 100644
--- a/src/modules/navigator/gpsfailure.cpp
+++ b/src/modules/navigator/gpsfailure.cpp
@@ -57,7 +57,12 @@
GpsFailure::GpsFailure(Navigator *navigator, const char *name) :
MissionBlock(navigator, name),
- _gpsf_state(GPSF_STATE_NONE)
+ _param_loitertime(this, "LT"),
+ _param_openlooploiter_roll(this, "R"),
+ _param_openlooploiter_pitch(this, "P"),
+ _param_openlooploiter_thrust(this, "TR"),
+ _gpsf_state(GPSF_STATE_NONE),
+ _timestamp_activation(0)
{
/* load initial params */
updateParams();
@@ -82,6 +87,7 @@ void
GpsFailure::on_activation()
{
_gpsf_state = GPSF_STATE_NONE;
+ _timestamp_activation = hrt_absolute_time();
updateParams();
advance_gpsf();
set_gpsf_item();
@@ -90,10 +96,34 @@ GpsFailure::on_activation()
void
GpsFailure::on_active()
{
- if (is_mission_item_reached()) {
- updateParams();
- advance_gpsf();
+
+ switch (_gpsf_state) {
+ case GPSF_STATE_LOITER: {
+ /* Position controller does not run in this mode:
+ * navigator has to publish an attitude setpoint */
+ _navigator->get_att_sp()->roll_body = M_DEG_TO_RAD_F * _param_openlooploiter_roll.get();
+ _navigator->get_att_sp()->pitch_body = M_DEG_TO_RAD_F * _param_openlooploiter_pitch.get();
+ _navigator->get_att_sp()->thrust = _param_openlooploiter_thrust.get();
+ _navigator->publish_att_sp();
+
+ /* Measure time */
+ hrt_abstime elapsed = hrt_elapsed_time(&_timestamp_activation);
+
+ //warnx("open loop loiter, posctl enabled %u, elapsed %.1fs, thrust %.2f",
+ //_navigator->get_control_mode()->flag_control_position_enabled, elapsed * 1e-6, (double)_param_openlooploiter_thrust.get());
+ if (elapsed > _param_loitertime.get() * 1e6f) {
+ /* no recovery, adavance the state machine */
+ warnx("gps not recovered, switch to next state");
+ advance_gpsf();
+ }
+ break;
+ }
+ case GPSF_STATE_TERMINATE:
set_gpsf_item();
+ advance_gpsf();
+ break;
+ default:
+ break;
}
}
@@ -102,68 +132,45 @@ GpsFailure::set_gpsf_item()
{
struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
- set_previous_pos_setpoint();
- _navigator->set_can_loiter_at_sp(false);
+ /* Set pos sp triplet to invalid to stop pos controller */
+ pos_sp_triplet->previous.valid = false;
+ pos_sp_triplet->current.valid = false;
+ pos_sp_triplet->next.valid = false;
switch (_gpsf_state) {
- case GPSF_STATE_LOITER: {
- //_mission_item.lat = (double)(_param_commsholdlat.get()) * 1.0e-7;
- //_mission_item.lon = (double)(_param_commsholdlon.get()) * 1.0e-7;
- //_mission_item.altitude_is_relative = false;
- //_mission_item.altitude = _param_commsholdalt.get();
- //_mission_item.yaw = NAN;
- //_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 = _navigator->get_acceptance_radius();
- //_mission_item.time_inside = _param_commsholdwaittime.get() < 0.0f ? 0.0f : _param_commsholdwaittime.get();
- //_mission_item.pitch_min = 0.0f;
- //_mission_item.autocontinue = true;
- //_mission_item.origin = ORIGIN_ONBOARD;
-
- //_navigator->set_can_loiter_at_sp(true);
- break;
- }
case GPSF_STATE_TERMINATE: {
- //_mission_item.lat = (double)(_param_airfieldhomelat.get()) * 1.0e-7;
- //_mission_item.lon = (double)(_param_airfieldhomelon.get()) * 1.0e-7;
- //_mission_item.altitude_is_relative = false;
- //_mission_item.altitude = _param_airfieldhomealt.get();
- //_mission_item.yaw = NAN;
- //_mission_item.loiter_radius = _navigator->get_loiter_radius();
- //_mission_item.loiter_direction = 1;
- //_mission_item.nav_cmd = NAV_CMD_LOITER_UNLIMITED;
- //_mission_item.acceptance_radius = _navigator->get_acceptance_radius();
- //_mission_item.pitch_min = 0.0f;
- //_mission_item.autocontinue = true;
- //_mission_item.origin = ORIGIN_ONBOARD;
-
- //_navigator->set_can_loiter_at_sp(true);
- break;
+ /* Request flight termination from the commander */
+ pos_sp_triplet->flight_termination = true;
+ warnx("request flight termination");
}
default:
break;
}
reset_mission_item_reached();
-
- /* convert mission item to current position setpoint and make it valid */
- mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
- pos_sp_triplet->next.valid = false;
-
_navigator->set_position_setpoint_triplet_updated();
}
void
GpsFailure::advance_gpsf()
{
+ updateParams();
+
switch (_gpsf_state) {
case GPSF_STATE_NONE:
_gpsf_state = GPSF_STATE_LOITER;
+ warnx("gpsf loiter");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: open loop loiter");
break;
case GPSF_STATE_LOITER:
_gpsf_state = GPSF_STATE_TERMINATE;
+ warnx("gpsf terminate");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no gps recovery, termination");
+ warnx("mavlink sent");
break;
+ case GPSF_STATE_TERMINATE:
+ warnx("gpsf end");
+ _gpsf_state = GPSF_STATE_END;
default:
break;
}