Firmware
mavlink_mission.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2015 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 
46 #pragma once
47 
48 #include <dataman/dataman.h>
49 #include <uORB/uORB.h>
50 
51 #include "mavlink_bridge_header.h"
52 #include "mavlink_rate_limiter.h"
53 
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
59 };
60 
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
68 };
69 
70 static constexpr uint64_t MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT = 5000000;
71 static constexpr uint64_t MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT = 250000;
72 
73 class Mavlink;
74 
76 {
77 public:
78  explicit MavlinkMissionManager(Mavlink *mavlink);
79 
81 
86  void send(const hrt_abstime t);
87 
88  void handle_message(const mavlink_message_t *msg);
89 
90  void check_active_mission(void);
91 
92 private:
93  enum MAVLINK_WPM_STATES _state {MAVLINK_WPM_STATE_IDLE};
94  enum MAV_MISSION_TYPE _mission_type {MAV_MISSION_TYPE_MISSION};
95 
96  uint64_t _time_last_recv{0};
97  uint64_t _time_last_sent{0};
98 
99  uint8_t _reached_sent_count{0};
100 
101  bool _int_mode{false};
102 
103  unsigned _filesystem_errcount{0};
104 
105  static dm_item_t _dataman_id;
106  dm_item_t _my_dataman_id{DM_KEY_WAYPOINTS_OFFBOARD_0};
107 
108  static bool _dataman_init;
109 
110  static uint16_t _count[3];
111  static int32_t _current_seq;
112 
113  int32_t _last_reached{-1};
114 
115  dm_item_t _transfer_dataman_id{DM_KEY_WAYPOINTS_OFFBOARD_1};
116 
117  uint16_t _transfer_count{0};
118  uint16_t _transfer_seq{0};
119 
120  int32_t _transfer_current_seq{-1};
121 
122  uint8_t _transfer_partner_sysid{0};
123  uint8_t _transfer_partner_compid{0};
124 
125  static bool _transfer_in_progress;
126 
127  int _offboard_mission_sub{-1};
128  int _mission_result_sub{-1};
129 
130  orb_advert_t _offboard_mission_pub{nullptr};
131 
132  static uint16_t _geofence_update_counter;
133  static uint16_t _safepoint_update_counter;
134  bool _geofence_locked{false};
135 
136  MavlinkRateLimiter _slow_rate_limiter{100 * 1000};
137 
138  Mavlink *_mavlink;
139 
140  static constexpr unsigned int FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT =
141  2;
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
146  };
150  uint16_t current_max_item_count();
151 
153  uint16_t current_item_count();
154 
155  /* do not allow top copying this class */
157  MavlinkMissionManager &operator = (const MavlinkMissionManager &);
158 
159  void init_offboard_mission();
160 
161  int update_active_mission(dm_item_t dataman_id, uint16_t count, int32_t seq);
162 
164  int update_geofence_count(unsigned count);
165 
167  int update_safepoint_count(unsigned count);
168 
170  int load_geofence_stats();
171 
173  int load_safepoint_stats();
174 
178  void send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type);
179 
189  void send_mission_current(uint16_t seq);
190 
191  void send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count, MAV_MISSION_TYPE mission_type);
192 
193  void send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq);
194 
195  void send_mission_request(uint8_t sysid, uint8_t compid, uint16_t seq);
196 
204  void send_mission_item_reached(uint16_t seq);
205 
206  void handle_mission_ack(const mavlink_message_t *msg);
207 
208  void handle_mission_set_current(const mavlink_message_t *msg);
209 
210  void handle_mission_request_list(const mavlink_message_t *msg);
211 
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);
215 
216  void handle_mission_count(const mavlink_message_t *msg);
217 
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);
221 
222  void handle_mission_clear_all(const mavlink_message_t *msg);
223 
231  int parse_mavlink_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item);
232 
240  int format_mavlink_mission_item(const struct mission_item_s *mission_item,
241  mavlink_mission_item_t *mavlink_mission_item);
242 
246  void switch_to_idle_state();
247 };
Global position setpoint in WGS84 coordinates.
Definition: navigation.h:145
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.
DATAMANAGER driver.
Definition: mavlink_mission.h:75
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Definition: mavlink_rate_limiter.h:47
void send(const hrt_abstime t)
Handle sending of messages.
Definition: mavlink_mission.cpp:485