51 #include "mavlink_bridge_header.h" 54 enum MAVLINK_WPM_STATES {
55 MAVLINK_WPM_STATE_IDLE = 0,
56 MAVLINK_WPM_STATE_SENDLIST,
57 MAVLINK_WPM_STATE_GETLIST,
58 MAVLINK_WPM_STATE_ENUM_END
61 enum MAVLINK_WPM_CODES {
62 MAVLINK_WPM_CODE_OK = 0,
63 MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED,
64 MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED,
65 MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS,
66 MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED,
67 MAVLINK_WPM_CODE_ENUM_END
70 static constexpr uint64_t MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT = 5000000;
71 static constexpr uint64_t MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT = 250000;
88 void handle_message(
const mavlink_message_t *msg);
90 void check_active_mission(
void);
93 enum MAVLINK_WPM_STATES _state {MAVLINK_WPM_STATE_IDLE};
94 enum MAV_MISSION_TYPE _mission_type {MAV_MISSION_TYPE_MISSION};
96 uint64_t _time_last_recv{0};
97 uint64_t _time_last_sent{0};
99 uint8_t _reached_sent_count{0};
101 bool _int_mode{
false};
103 unsigned _filesystem_errcount{0};
106 dm_item_t _my_dataman_id{DM_KEY_WAYPOINTS_OFFBOARD_0};
108 static bool _dataman_init;
110 static uint16_t _count[3];
111 static int32_t _current_seq;
113 int32_t _last_reached{-1};
115 dm_item_t _transfer_dataman_id{DM_KEY_WAYPOINTS_OFFBOARD_1};
117 uint16_t _transfer_count{0};
118 uint16_t _transfer_seq{0};
120 int32_t _transfer_current_seq{-1};
122 uint8_t _transfer_partner_sysid{0};
123 uint8_t _transfer_partner_compid{0};
125 static bool _transfer_in_progress;
127 int _offboard_mission_sub{-1};
128 int _mission_result_sub{-1};
132 static uint16_t _geofence_update_counter;
133 static uint16_t _safepoint_update_counter;
134 bool _geofence_locked{
false};
140 static constexpr
unsigned int FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT =
142 static constexpr uint16_t MAX_COUNT[] = {
143 DM_KEY_WAYPOINTS_OFFBOARD_0_MAX,
144 DM_KEY_FENCE_POINTS_MAX - 1,
145 DM_KEY_SAFE_POINTS_MAX - 1
150 uint16_t current_max_item_count();
153 uint16_t current_item_count();
159 void init_offboard_mission();
161 int update_active_mission(
dm_item_t dataman_id, uint16_t count, int32_t seq);
164 int update_geofence_count(
unsigned count);
167 int update_safepoint_count(
unsigned count);
170 int load_geofence_stats();
173 int load_safepoint_stats();
178 void send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type);
189 void send_mission_current(uint16_t seq);
191 void send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count, MAV_MISSION_TYPE mission_type);
193 void send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq);
195 void send_mission_request(uint8_t sysid, uint8_t compid, uint16_t seq);
204 void send_mission_item_reached(uint16_t seq);
206 void handle_mission_ack(
const mavlink_message_t *msg);
208 void handle_mission_set_current(
const mavlink_message_t *msg);
210 void handle_mission_request_list(
const mavlink_message_t *msg);
212 void handle_mission_request(
const mavlink_message_t *msg);
213 void handle_mission_request_int(
const mavlink_message_t *msg);
214 void handle_mission_request_both(
const mavlink_message_t *msg);
216 void handle_mission_count(
const mavlink_message_t *msg);
218 void handle_mission_item(
const mavlink_message_t *msg);
219 void handle_mission_item_int(
const mavlink_message_t *msg);
220 void handle_mission_item_both(
const mavlink_message_t *msg);
222 void handle_mission_clear_all(
const mavlink_message_t *msg);
231 int parse_mavlink_mission_item(
const mavlink_mission_item_t *mavlink_mission_item,
struct mission_item_s *mission_item);
240 int format_mavlink_mission_item(
const struct mission_item_s *mission_item,
241 mavlink_mission_item_t *mavlink_mission_item);
246 void switch_to_idle_state();
Global position setpoint in WGS84 coordinates.
Definition: navigation.h:145
Message rate limiter definition.
dm_item_t
Types of items that the data manager can store.
Definition: dataman.h:50
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
API for the uORB lightweight object broker.
Definition: mavlink_mission.h:75
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Definition: mavlink_main.h:98
Definition: mavlink_rate_limiter.h:47
void send(const hrt_abstime t)
Handle sending of messages.
Definition: mavlink_mission.cpp:485