0.3.0
Loading...
Searching...
No Matches
autopilot_interface.hpp
Go to the documentation of this file.
1/****************************************************************************
2 *
3 * Copyright (c) 2014 MAVlink Development Team. All rights reserved.
4 * Author: Trent Lukaczyk, <aerialhedgehog@gmail.com>
5 * Jaycee Lock, <jaycee.lock@gmail.com>
6 * Lorenz Meier, <lm@inf.ethz.ch>
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * 1. Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * 2. Redistributions in binary form must reproduce the above copyright
15 * notice, this list of conditions and the following disclaimer in
16 * the documentation and/or other materials provided with the
17 * distribution.
18 * 3. Neither the name PX4 nor the names of its contributors may be
19 * used to endorse or promote products derived from this software
20 * without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
29 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
30 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 ****************************************************************************/
36
50#pragma once
51
52#if __linux__ || __APPLE__
53// ------------------------------------------------------------------------------
54// Includes
55// ------------------------------------------------------------------------------
56
57 #include "generic_port.hpp"
58
59 #include <signal.h> // NOLINT(hicpp-deprecated-headers,modernize-deprecated-headers) // FIXME: inclusion of deprecated C++ header 'signal.h'; consider using 'csignal' instead
60 #include <time.h> // NOLINT(hicpp-deprecated-headers,modernize-deprecated-headers) // FIXME: inclusion of deprecated C++ header 'time.h'; consider using 'ctime' instead
61 #include <sys/time.h>
62 #include <pthread.h> // This uses POSIX Threads
63 #include <unistd.h> // UNIX standard function definitions
64 #include <mutex>
65 #include <cstdint>
66 #include <memory>
67
68 #include <mavlink/common/mavlink.h>
69
70// ------------------------------------------------------------------------------
71// Defines
72// ------------------------------------------------------------------------------
73
108// bit number 876543210987654321
109constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_POSITION = 0b0000110111111000;
110constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_VELOCITY = 0b0000110111000111;
111constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_ACCELERATION = 0b0000110000111111;
112constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_FORCE = 0b0000111000111111;
113constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_YAW_ANGLE = 0b0000100111111111;
114constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_YAW_RATE = 0b0000010111111111;
115
116constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_TAKEOFF = 0x1000;
117constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_LAND = 0x2000;
118constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_LOITER = 0x3000;
119constexpr size_t MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_IDLE = 0x4000;
120
122enum AUTOPILOT_MODE_ : uint8_t
123{
124 AUTOPILOT_MODE_STABILIZED = 0,
125 AUTOPILOT_MODE_ACRO = 1,
126 AUTOPILOT_MODE_ALTHOLD = 2,
127 AUTOPILOT_MODE_AUTO = 3,
128 AUTOPILOT_MODE_GUIDED = 4,
129 AUTOPILOT_MODE_LOITER = 5,
130 AUTOPILOT_MODE_RTL = 6,
131 AUTOPILOT_MODE_CIRCLE = 7,
132 AUTOPILOT_MODE_LAND = 9,
133 AUTOPILOT_MODE_DRIFT = 11,
134 AUTOPILOT_MODE_SPORT = 13,
135 AUTOPILOT_MODE_FLIP = 14,
136 AUTOPILOT_MODE_AUTOTUNE = 15,
137 AUTOPILOT_MODE_POSHOLD = 16,
138 AUTOPILOT_MODE_BRAKE = 17,
139 AUTOPILOT_MODE_THROW = 18,
140 AUTOPILOT_MODE_AVOIDADSB = 19,
141 AUTOPILOT_MODE_GUIDEDNOGPS = 20,
142 AUTOPILOT_MODE_SMARTRTL = 21,
143 AUTOPILOT_MODE_FOLOWHOLD = 22,
144 AUTOPILOT_MODE_FOLLOW = 23,
145 AUTOPILOT_MODE_ZIGZAG = 24,
146 AUTOPILOT_MODE_SYSTEMID = 25,
147};
148
149// ------------------------------------------------------------------------------
150// Prototypes
151// ------------------------------------------------------------------------------
152
153// helper functions
154
156uint64_t get_time_usec();
157
163void set_position(float x, float y, float z, mavlink_set_position_target_local_ned_t& sp);
164
170void set_velocity(float vx, float vy, float vz, mavlink_set_position_target_local_ned_t& sp);
171
177void set_acceleration(float ax, float ay, float az, mavlink_set_position_target_local_ned_t& sp);
178
182void set_yaw(float yaw, mavlink_set_position_target_local_ned_t& sp);
183
187void set_yaw_rate(float yaw_rate, mavlink_set_position_target_local_ned_t& sp);
188
191void* start_autopilot_interface_read_thread(void* args);
192
195void* start_autopilot_interface_write_thread(void* args);
196
197// ------------------------------------------------------------------------------
198// Data Structures
199// ------------------------------------------------------------------------------
200
202struct Time_Stamps
203{
204 Time_Stamps()
205 {
206 reset_timestamps();
207 }
208
209 uint64_t heartbeat{};
210 uint64_t sys_status{};
211 uint64_t battery_status{};
212 uint64_t radio_status{};
213 uint64_t local_position_ned{};
214 uint64_t global_position_int{};
215 uint64_t position_target_local_ned{};
216 uint64_t position_target_global_int{};
217 uint64_t highres_imu{};
218 uint64_t attitude{};
219
221 void reset_timestamps()
222 {
223 heartbeat = 0;
224 sys_status = 0;
225 battery_status = 0;
226 radio_status = 0;
227 local_position_ned = 0;
228 global_position_int = 0;
229 position_target_local_ned = 0;
230 position_target_global_int = 0;
231 highres_imu = 0;
232 attitude = 0;
233 }
234};
235
237struct Mavlink_Messages
238{
239 int sysid{};
240 int compid{};
241
242 mavlink_heartbeat_t heartbeat{};
243 mavlink_sys_status_t sys_status{};
244 mavlink_battery_status_t battery_status{};
245 mavlink_radio_status_t radio_status{};
246 mavlink_local_position_ned_t local_position_ned{};
247 mavlink_global_position_int_t global_position_int{};
248 mavlink_position_target_local_ned_t position_target_local_ned{};
249 mavlink_position_target_global_int_t position_target_global_int{};
250 mavlink_highres_imu_t highres_imu{};
251 mavlink_attitude_t attitude{};
252
253 // System Parameters?
254
255 Time_Stamps time_stamps;
256
258 void reset_timestamps()
259 {
260 time_stamps.reset_timestamps();
261 }
262};
263
264// ----------------------------------------------------------------------------------
265// Autopilot Interface Class
266// ----------------------------------------------------------------------------------
267/*
268 * Autopilot Interface Class
269 *
270 * This starts two threads for read and write over MAVlink. The read thread
271 * listens for any MAVlink message and pushes it to the current_messages
272 * attribute. The write thread at the moment only streams a position target
273 * in the local NED frame (mavlink_set_position_target_local_ned_t), which
274 * is changed by using the method update_setpoint(). Sending these messages
275 * are only half the requirement to get response from the autopilot, a signal
276 * to enter "offboard_control" mode is sent by using the enable_offboard_control()
277 * method. Signal the exit of this mode with disable_offboard_control(). It's
278 * important that one way or another this program signals offboard mode exit,
279 * otherwise the vehicle will go into failsafe.
280 */
281
283class Autopilot_Interface
284{
285 public:
287 Autopilot_Interface() = default;
289 explicit Autopilot_Interface(const std::shared_ptr<Generic_Port>& port_);
291 ~Autopilot_Interface() = default;
293 Autopilot_Interface(const Autopilot_Interface&) = delete;
295 Autopilot_Interface(Autopilot_Interface&&) = delete;
297 Autopilot_Interface& operator=(const Autopilot_Interface&) = delete;
299 Autopilot_Interface& operator=(Autopilot_Interface&&) = delete;
300
301 uint64_t write_count{};
302 char reading_status{};
303 char writing_status{};
304 char control_status{};
305
306 int system_id{};
307 int autopilot_id{};
308 int companion_id{};
309
310 // MOCAP Variables
311 float mocap_w{};
312 float mocap_x{};
313 float mocap_y{};
314 float mocap_z{};
315 bool MOCAP_Active = false;
316 double MOCAP_Frequency = 0;
317
318 // GPS Variables
319 int32_t gps_lat_d{};
320 int32_t gps_lon_d{};
321 float gps_alt{};
322 float gps_vn{};
323 float gps_ve{};
324 float gps_vd{};
325 uint32_t gps_time_week_ms{};
326 uint16_t gps_time_week{};
327 bool GPS_Active = false;
328 double GPS_Frequency = 0;
329
330 Mavlink_Messages current_messages{};
331 mavlink_set_position_target_local_ned_t initial_position{};
332
335 void update_setpoint(mavlink_set_position_target_local_ned_t setpoint);
336
338 void read_messages();
339
342 int write_message(mavlink_message_t message);
343
346 int arm_disarm(bool flag);
347
349 void enable_offboard_control();
350
352 void disable_offboard_control();
353
355 void start();
356
358 void stop();
359
361 void start_read_thread();
362
364 void start_write_thread();
365
368 void handle_quit(int sig);
369
379 int GPS_Input(int32_t lat_d, int32_t lon_d, float alt, float vn, float ve, float vd, uint32_t time_week_ms, uint16_t time_week);
380
386 int MOCAP_Input(float w, float x, float y, float z);
387
393 void setMOCAP(float w, float x, float y, float z);
394
404 void setGPS(int32_t lat_d, int32_t lon_d, float alt, float vn, float ve, float vd, uint32_t time_week_ms, uint16_t time_week);
405
408 void setPort(const std::shared_ptr<Generic_Port>& port_new);
409
412 void setGPS_Frequency(double _Frequency);
413
416 void setMOCAP_Frequency(double _Frequency);
417
420 void setGPS_Active(bool _Active);
421
424 void setMOCAP_Active(bool _Active);
425
426 private:
427 std::shared_ptr<Generic_Port> port;
428
429 bool time_to_exit = false;
430
431 pthread_t read_tid{};
432 pthread_t write_tid{};
433
435 struct
436 {
437 std::mutex mutex;
438 mavlink_set_position_target_local_ned_t data{};
439 } current_setpoint;
440
442 void read_thread();
443
445 void write_thread();
446
449 int toggle_offboard_control(bool flag);
450
452 void write_setpoint();
453};
454
455#endif
void start()
Starts the Thread.
void stop()
Stops the Thread.
Generic interface definition.