PX4 Firmware
PX4 Autopilot Software http://px4.io
datalinkloss.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 /**
34  * @file datalinkloss.cpp
35  * Helper class for Data Link Loss Mode according to the OBC rules
36  *
37  * @author Thomas Gubler <thomasgubler@gmail.com>
38  */
39 
40 #include <string.h>
41 #include <stdlib.h>
42 #include <math.h>
43 #include <fcntl.h>
44 
45 #include <systemlib/mavlink_log.h>
46 #include <systemlib/err.h>
47 #include <lib/ecl/geo/geo.h>
48 #include <navigator/navigation.h>
49 
50 #include <uORB/uORB.h>
51 #include <uORB/topics/mission.h>
53 
54 #include "navigator.h"
55 #include "datalinkloss.h"
56 
58  MissionBlock(navigator),
59  ModuleParams(navigator),
60  _dll_state(DLL_STATE_NONE)
61 {
62 }
63 
64 void
66 {
67  /* reset DLL state only if setpoint moved */
69  _dll_state = DLL_STATE_NONE;
70  }
71 }
72 
73 void
75 {
76  _dll_state = DLL_STATE_NONE;
77  advance_dll();
78  set_dll_item();
79 }
80 
81 void
83 {
85  advance_dll();
86  set_dll_item();
87  }
88 }
89 
90 void
92 {
94 
95  pos_sp_triplet->previous = pos_sp_triplet->current;
97 
98  switch (_dll_state) {
99  case DLL_STATE_FLYTOCOMMSHOLDWP: {
100  _mission_item.lat = (double)(_param_nav_dll_ch_lat.get()) * 1.0e-7;
101  _mission_item.lon = (double)(_param_nav_dll_ch_lon.get()) * 1.0e-7;
103  _mission_item.altitude = _param_nav_dll_ch_alt.get();
104  _mission_item.yaw = NAN;
108  _mission_item.time_inside = _param_nav_dll_ch_t.get() < 0.0f ? 0.0f : _param_nav_dll_ch_t.get();
111 
113  break;
114  }
115 
116  case DLL_STATE_FLYTOAIRFIELDHOMEWP: {
117  _mission_item.lat = (double)(_param_nav_ah_lat.get()) * 1.0e-7;
118  _mission_item.lon = (double)(_param_nav_ah_lon.get()) * 1.0e-7;
120  _mission_item.altitude = _param_nav_ah_alt.get();
121  _mission_item.yaw = NAN;
124  _mission_item.time_inside = _param_nav_dll_ah_t.get() < 0.0f ? 0.0f : _param_nav_dll_ah_t.get();
128 
130  break;
131  }
132 
133  case DLL_STATE_TERMINATE: {
134  /* Request flight termination from the commander */
138  warnx("not switched to manual: request flight termination");
139  pos_sp_triplet->previous.valid = false;
140  pos_sp_triplet->current.valid = false;
141  pos_sp_triplet->next.valid = false;
142  break;
143  }
144 
145  default:
146  break;
147  }
148 
150 
151  /* convert mission item to current position setpoint and make it valid */
153  pos_sp_triplet->next.valid = false;
154 
156 }
157 
158 void
160 {
161  switch (_dll_state) {
162  case DLL_STATE_NONE:
163 
164  /* Check the number of data link losses. If above home fly home directly */
165  /* if number of data link losses limit is not reached fly to comms hold wp */
166  if (_navigator->get_vstatus()->data_link_lost_counter > _param_nav_dll_n.get()) {
167  warnx("%d data link losses, limit is %d, fly to airfield home",
168  _navigator->get_vstatus()->data_link_lost_counter, _param_nav_dll_n.get());
169  mavlink_log_critical(_navigator->get_mavlink_log_pub(), "too many DL losses, fly to airfield home");
173  _dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
174 
175  } else {
176  if (!_param_nav_dll_chsk.get()) {
177  warnx("fly to comms hold, datalink loss counter: %d", _navigator->get_vstatus()->data_link_lost_counter);
178  mavlink_log_critical(_navigator->get_mavlink_log_pub(), "fly to comms hold");
179  _dll_state = DLL_STATE_FLYTOCOMMSHOLDWP;
180 
181  } else {
182  /* comms hold wp not active, fly to airfield home directly */
183  warnx("Skipping comms hold wp. Flying directly to airfield home");
184  mavlink_log_critical(_navigator->get_mavlink_log_pub(), "fly to airfield home, comms hold skipped");
185  _dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
186  }
187  }
188 
189  break;
190 
191  case DLL_STATE_FLYTOCOMMSHOLDWP:
192  warnx("fly to airfield home");
193  mavlink_log_critical(_navigator->get_mavlink_log_pub(), "fly to airfield home");
194  _dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
198  break;
199 
200  case DLL_STATE_FLYTOAIRFIELDHOMEWP:
201  _dll_state = DLL_STATE_TERMINATE;
202  warnx("time is up, state should have been changed manually by now");
203  mavlink_log_critical(_navigator->get_mavlink_log_pub(), "no manual control, terminating");
207  break;
208 
209  case DLL_STATE_TERMINATE:
210  warnx("dll end");
211  _dll_state = DLL_STATE_END;
212  break;
213 
214  default:
215  break;
216  }
217 }
uint8_t data_link_lost_counter
float get_acceptance_radius()
Get the acceptance radius.
API for the uORB lightweight object broker.
Definition of geo / math functions to perform geodesic calculations.
float altitude
altitude in meters (AMSL)
Definition: navigation.h:160
uint16_t autocontinue
true if next waypoint should follow after this one
Definition: navigation.h:177
float acceptance_radius
default radius in which the mission is accepted as reached in meters
Definition: navigation.h:155
struct position_setpoint_s next
uint16_t origin
how the mission item was generated
Definition: navigation.h:177
struct position_setpoint_s previous
Helper class for Data Link Loss Mode acording to the OBC rules.
bool get_can_loiter_at_sp()
Definition: navigator.h:170
double lon
longitude in degrees
Definition: navigation.h:147
Navigator * _navigator
struct position_setpoint_s current
mission_item_s _mission_item
uint16_t nav_cmd
navigation command
Definition: navigation.h:165
#define warnx(...)
Definition: err.h:95
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
void reset_mission_item_reached()
Reset all reached flags.
float time_inside
time that the MAV should stay inside the radius before advancing in seconds
Definition: navigation.h:151
struct position_setpoint_triplet_s * get_position_setpoint_triplet()
Definition: navigator.h:153
struct mission_result_s * get_mission_result()
Definition: navigator.h:152
bool mission_item_to_position_setpoint(const mission_item_s &item, position_setpoint_s *sp)
Convert a mission item to a position setpoint.
bool is_mission_item_reached()
Check if mission item has been reached.
float get_loiter_radius()
Definition: navigator.h:171
orb_advert_t * get_mavlink_log_pub()
Definition: navigator.h:261
struct vehicle_status_s * get_vstatus()
Definition: navigator.h:159
void set_mission_result_updated()
Definition: navigator.h:146
float yaw
in radians NED -PI..+PI, NAN means don&#39;t change yaw
Definition: navigation.h:157
float loiter_radius
loiter radius in meters, 0 for a VTOL to hover, negative for counter-clockwise
Definition: navigation.h:156
void set_can_loiter_at_sp(bool can_loiter)
Setters.
Definition: navigator.h:144
void set_position_setpoint_triplet_updated()
Definition: navigator.h:145
uint16_t altitude_is_relative
true if altitude is relative from start point
Definition: navigation.h:177
double lat
latitude in degrees
Definition: navigation.h:146