Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
mavlink.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Freek van Tienen <freek.v.tienen@gmail.com>
3  *
4  * This file is part of paparazzi.
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, write to
18  * the Free Software Foundation, 59 Temple Place - Suite 330,
19  * Boston, MA 02111-1307, USA.
20  *
21  */
22 
28 
29 // include mavlink headers, but ignore some warnings
30 #pragma GCC diagnostic push
31 #pragma GCC diagnostic ignored "-Waddress-of-packed-member"
32 #pragma GCC diagnostic ignored "-Wswitch-default"
33 #pragma GCC diagnostic ignored "-Wuninitialized"
34 #include "mavlink/ardupilotmega/mavlink.h"
35 #pragma GCC diagnostic pop
36 
37 #if PERIODIC_TELEMETRY
38 #define PERIODIC_C_MAVLINK
40 #include "generated/periodic_telemetry.h"
41 #ifndef TELEMETRY_MAVLINK_NB_MSG
42 #warning Using hardcoded msg periods. To customize specify a <process name="Mavlink" type="mavlink"> in your telemetry file.
43 #endif
44 #endif
45 
46 #include "generated/airframe.h"
47 #include "generated/modules.h"
48 #include "generated/settings.h"
49 #include "generated/flight_plan.h"
50 
51 #include "mcu_periph/sys_time.h"
53 #include "state.h"
54 #include "pprz_version.h"
55 #include "autopilot.h"
56 #include "autopilot_guided.h"
57 
58 #if defined RADIO_CONTROL
60 #endif
61 
62 // Change the autopilot identification code: by default identify as PPZ autopilot: alternatively as MAV_AUTOPILOT_ARDUPILOTMEGA
63 #ifndef MAV_AUTOPILOT_ID
64 #define MAV_AUTOPILOT_ID MAV_AUTOPILOT_PPZ
65 #endif
66 
68 
69 // for UINT16_MAX
70 #include <stdint.h>
71 
72 mavlink_system_t mavlink_system;
73 
74 static uint8_t mavlink_params_idx = NB_SETTING;
78 static char mavlink_param_names[NB_SETTING][16 + 1] = SETTINGS_NAMES_SHORT;
82 
83 void mavlink_common_message_handler(const mavlink_message_t *msg);
84 
85 static void mavlink_send_extended_sys_state(struct transport_tx *trans, struct link_device *dev);
86 static void mavlink_send_heartbeat(struct transport_tx *trans, struct link_device *dev);
87 static void mavlink_send_sys_status(struct transport_tx *trans, struct link_device *dev);
88 static void mavlink_send_system_time(struct transport_tx *trans, struct link_device *dev);
89 static void mavlink_send_attitude(struct transport_tx *trans, struct link_device *dev);
90 static void mavlink_send_local_position_ned(struct transport_tx *trans, struct link_device *dev);
91 static void mavlink_send_global_position_int(struct transport_tx *trans, struct link_device *dev);
92 static void mavlink_send_params(struct transport_tx *trans, struct link_device *dev);
93 static void mavlink_send_autopilot_version(struct transport_tx *trans, struct link_device *dev);
94 static void mavlink_send_attitude_quaternion(struct transport_tx *trans, struct link_device *dev);
95 static void mavlink_send_gps_raw_int(struct transport_tx *trans, struct link_device *dev);
96 static void mavlink_send_rc_channels(struct transport_tx *trans, struct link_device *dev);
97 static void mavlink_send_battery_status(struct transport_tx *trans, struct link_device *dev);
98 static void mavlink_send_gps_global_origin(struct transport_tx *trans, struct link_device *dev);
99 static void mavlink_send_gps_status(struct transport_tx *trans, struct link_device *dev);
100 static void mavlink_send_vfr_hud(struct transport_tx *trans, struct link_device *dev);
101 
102 
107 #ifndef MAVLINK_SYSID
108 #define MAVLINK_SYSID AC_ID
109 #endif
110 
111 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
112 struct telemetry_cb_slots mavlink_cbs[TELEMETRY_MAVLINK_NB_MSG] = TELEMETRY_MAVLINK_CBS;
113 struct periodic_telemetry mavlink_telemetry = { TELEMETRY_MAVLINK_NB_MSG, mavlink_cbs };
114 #endif
115 
116 void mavlink_init(void)
117 {
118  mavlink_system.sysid = MAVLINK_SYSID; // System ID, 1-255
119  mavlink_system.compid = MAV_COMP_ID_AUTOPILOT1; // Component/Subsystem ID, 1-255
120 
121  get_pprz_git_version(custom_version);
122 
124 
125 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
126  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_HEARTBEAT, mavlink_send_heartbeat);
127  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_SYS_STATUS, mavlink_send_sys_status);
128  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, mavlink_send_extended_sys_state);
129  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_SYSTEM_TIME, mavlink_send_system_time);
130  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_ATTITUDE, mavlink_send_attitude);
131  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, mavlink_send_attitude_quaternion);
132  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_LOCAL_POSITION_NED, mavlink_send_local_position_ned);
133  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, mavlink_send_global_position_int);
134  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_GPS_RAW_INT, mavlink_send_gps_raw_int);
135  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_RC_CHANNELS, mavlink_send_rc_channels);
136  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_BATTERY_STATUS, mavlink_send_battery_status);
137  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_AUTOPILOT_VERSION, mavlink_send_autopilot_version);
138  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, mavlink_send_gps_global_origin);
139  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_GPS_STATUS, mavlink_send_gps_status);
140  register_periodic_telemetry(&mavlink_telemetry, MAVLINK_MSG_ID_VFR_HUD, mavlink_send_vfr_hud);
141 #endif
142 }
143 
149 {
150 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
151  // send periodic mavlink messages as defined in the Mavlink process of the telemetry xml file
152  // transport and device not used here yet...
153  periodic_telemetry_send_Mavlink(&mavlink_telemetry, NULL, NULL);
154 #endif
155 }
156 
162 {
163 #if !defined (TELEMETRY_MAVLINK_NB_MSG)
164  // use these hardcoded periods if no Mavlink process in telemetry file
165  RunOnceEvery(2, mavlink_send_heartbeat(NULL, NULL));
166  RunOnceEvery(5, mavlink_send_sys_status(NULL, NULL));
167  RunOnceEvery(20, mavlink_send_system_time(NULL, NULL));
168  RunOnceEvery(10, mavlink_send_attitude(NULL, NULL));
169  RunOnceEvery(5, mavlink_send_attitude_quaternion(NULL, NULL));
170  RunOnceEvery(4, mavlink_send_local_position_ned(NULL, NULL));
171  RunOnceEvery(5, mavlink_send_global_position_int(NULL, NULL));
172  RunOnceEvery(6, mavlink_send_gps_raw_int(NULL, NULL));
173  RunOnceEvery(5, mavlink_send_rc_channels(NULL, NULL));
174  RunOnceEvery(21, mavlink_send_battery_status(NULL, NULL));
175  RunOnceEvery(32, mavlink_send_autopilot_version(NULL, NULL));
176  RunOnceEvery(33, mavlink_send_gps_global_origin(NULL, NULL));
177  RunOnceEvery(10, mavlink_send_gps_status(NULL, NULL));
178  RunOnceEvery(10, mavlink_send_vfr_hud(NULL, NULL));
179 #endif
180 
181  // if requested, send params at 5Hz until all sent
182  RunOnceEvery(2, mavlink_send_params(NULL, NULL));
183 
185 }
186 
187 static int16_t settings_idx_from_param_id(char *param_id)
188 {
189  int i, j;
190  int16_t settings_idx = -1;
191 
192  // Go trough all the settings to search the ID
193  for (i = 0; i < NB_SETTING; i++) {
194  for (j = 0; j < 16; j++) {
195  if (mavlink_param_names[i][j] != param_id[j]) {
196  break;
197  }
198 
199  if (mavlink_param_names[i][j] == '\0') {
200  settings_idx = i;
201  return settings_idx;
202  }
203  }
204 
205  if (mavlink_param_names[i][j] == '\0') {
206  break;
207  }
208  }
209  return settings_idx;
210 }
211 
215 void mavlink_event(void)
216 {
217  mavlink_message_t msg;
218  mavlink_status_t status;
219 
220  // Check uplink
221  while (MAVLinkChAvailable()) {
222  char test = MAVLinkGetch();
223 
224  // When we receive a message
225  if (mavlink_parse_char(MAVLINK_COMM_0, test, &msg, &status)) {
228  }
229  }
230 }
231 
232 void mavlink_common_message_handler(const mavlink_message_t *msg)
233 {
234  switch (msg->msgid) {
235  case MAVLINK_MSG_ID_PLAY_TUNE:
236  case MAVLINK_MSG_ID_PLAY_TUNE_V2:
237  DOWNLINK_SEND_INFO_MSG(DefaultChannel, DefaultDevice, strlen("PLAY TUNE"), "PLAY TUNE");
238  break;
239 
240  case MAVLINK_MSG_ID_HEARTBEAT:
241  break;
242 
243  /* When requesting data streams say we can't send them */
244  case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: {
245  mavlink_request_data_stream_t cmd;
246  mavlink_msg_request_data_stream_decode(msg, &cmd);
247 
248  mavlink_msg_data_stream_send(MAVLINK_COMM_0, cmd.req_stream_id, 0, 0);
250  break;
251  }
252 
253  /* Override channels with RC */
254  case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: {
255  mavlink_rc_channels_override_t cmd;
256  mavlink_msg_rc_channels_override_decode(msg, &cmd);
257 #if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK
258  uint8_t thrust = (cmd.chan3_raw - 950) * 127 / 1100;
259  int8_t roll = -(cmd.chan1_raw - 1500) * 255 / 1100 / 2;
260  int8_t pitch = -(cmd.chan2_raw - 1500) * 255 / 1100 / 2;
261  int8_t yaw = -(cmd.chan4_raw - 1500) * 255 / 1100;
262  int8_t temp_rc[4] = {roll, pitch, yaw, thrust};
263  parse_rc_up_datalink(4, temp_rc);
264  //printf("RECEIVED: RC Channel Override for: %d/%d: throttle: %d; roll: %d; pitch: %d; yaw: %d;\r\n",
265  // cmd.target_system, cmd.target_component, thrust, roll, pitch, yaw);
266 #endif
267  break;
268  }
269 
270  /* When a request is made of the parameters list */
271  case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
272  mavlink_params_idx = 0;
273  break;
274  }
275 
276  /* When a request os made for a specific parameter */
277  case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
278  mavlink_param_request_read_t cmd;
279  mavlink_msg_param_request_read_decode(msg, &cmd);
280 
281  // First check param_index and search for the ID if needed
282  if (cmd.param_index == -1) {
283  cmd.param_index = settings_idx_from_param_id(cmd.param_id);
284  }
285 
286  // Send message only if the param_index was found (Coverity Scan)
287  if (cmd.param_index > -1) {
288  mavlink_msg_param_value_send(MAVLINK_COMM_0,
289  mavlink_param_names[cmd.param_index],
290  settings_get_value(cmd.param_index),
291  MAV_PARAM_TYPE_REAL32,
292  NB_SETTING,
293  cmd.param_index);
295  }
296  break;
297  }
298 
299  case MAVLINK_MSG_ID_PARAM_SET: {
300  mavlink_param_set_t set;
301  mavlink_msg_param_set_decode(msg, &set);
302 
303  // Check if this message is for this system
304  if ((uint8_t) set.target_system == AC_ID) {
305  int16_t idx = settings_idx_from_param_id(set.param_id);
306 
307  // setting found
308  if (idx >= 0) {
309  // Only write if new value is NOT "not-a-number"
310  // AND is NOT infinity
311  if (set.param_type == MAV_PARAM_TYPE_REAL32 &&
312  !isnan(set.param_value) && !isinf(set.param_value)) {
313  DlSetting(idx, set.param_value);
314  // Report back new value
315  mavlink_msg_param_value_send(MAVLINK_COMM_0,
317  settings_get_value(idx),
318  MAV_PARAM_TYPE_REAL32,
319  NB_SETTING,
320  idx);
322  }
323  }
324  }
325  }
326  break;
327 
328 #ifdef ROTORCRAFT_FIRMWARE
329  /* only for rotorcraft */
330  case MAVLINK_MSG_ID_COMMAND_LONG: {
331  mavlink_command_long_t cmd;
332  mavlink_msg_command_long_decode(msg, &cmd);
333  // Check if this message is for this system
334  if ((uint8_t) cmd.target_system == AC_ID) {
335  uint8_t result = MAV_RESULT_UNSUPPORTED;
336  switch (cmd.command) {
337 
338  case MAV_CMD_SET_MESSAGE_INTERVAL:
339  case MAV_CMD_DO_SET_MODE: {
340  char error_msg[200];
341  int rc = snprintf(error_msg, 200, "Do set %d: %0.0f %0.0f (%d)", cmd.command, cmd.param1, cmd.param2, cmd.target_system);
342  if (rc > 0) {
343  DOWNLINK_SEND_INFO_MSG(DefaultChannel, DefaultDevice, rc, error_msg);
344  }
345  result = MAV_RESULT_ACCEPTED;
346  break;
347  }
348 
349  case MAV_CMD_NAV_GUIDED_ENABLE:
350  MAVLINK_DEBUG("got cmd NAV_GUIDED_ENABLE: %f\n", cmd.param1);
351  result = MAV_RESULT_FAILED;
352  if (cmd.param1 > 0.5) {
355  result = MAV_RESULT_ACCEPTED;
356  }
357  }
358  else {
359  // turn guided mode off - to what? maybe NAV? or MODE_AUTO2?
360  }
361  break;
362 
363  case MAV_CMD_COMPONENT_ARM_DISARM:
364  /* supposed to use this command to arm or SET_MODE?? */
365  MAVLINK_DEBUG("got cmd COMPONENT_ARM_DISARM: %f\n", cmd.param1);
366  result = MAV_RESULT_FAILED;
367  if (cmd.param1 > 0.5) {
370  result = MAV_RESULT_ACCEPTED;
371  }
372  else {
375  result = MAV_RESULT_ACCEPTED;
376  }
377  break;
378 
379  default:
380  break;
381  }
382  // confirm command with result
383  mavlink_msg_command_ack_send(MAVLINK_COMM_0, cmd.command, result, 0, UINT8_MAX, msg->sysid, msg->compid);
385  }
386  break;
387  }
388 
389 #ifdef WP_ML_global_target
390  case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: {
391  mavlink_set_position_target_global_int_t target;
392  mavlink_msg_set_position_target_global_int_decode(msg, &target);
393 
394  // Check if this message is for this system
395  //if (target.target_system == AC_ID) {
396  MAVLINK_DEBUG("SET_POSITION_TARGET_GLOBAL_INT, type_mask: %d, frame: %d\n", target.type_mask, target.coordinate_frame);
397  /* if position and yaw bits are not set to ignored, use only position for now */
398  if (target.coordinate_frame == MAV_FRAME_GLOBAL || target.coordinate_frame == MAV_FRAME_GLOBAL_INT) {
399  MAVLINK_DEBUG("set position target, frame MAV_FRAME_GLOBAL %f \n", target.alt);
400  struct NedCoor_i ned;
401  //struct NedCoor_f ned_f;
402  struct LlaCoor_i lla;
403  lla.lat = target.lat_int;
404  lla.lon = target.lon_int;
405  lla.alt = MM_OF_M(target.alt);
407  //NED_FLOAT_OF_BFP(ned_f, ned);
408  //autopilot_guided_goto_ned(ned_f.x, ned_f.y, ned_f.z, target.yaw);
409  waypoint_set_latlon(WP_ML_global_target, &lla);
410  waypoint_set_alt(WP_ML_global_target, target.alt);
411 
412  // Downlink the new waypoint
413  uint8_t wp_id = WP_ML_global_target;
414  int32_t hmsl = lla.alt - stateGetNedOrigin_i()->alt + stateGetHmslOrigin_i();
415  DOWNLINK_SEND_WP_MOVED_LLA(DefaultChannel, DefaultDevice, &wp_id,
416  &lla.lat, &lla.lon, &hmsl);
417 
418  }
419  break;
420  }
421 #endif
422 
423  case MAVLINK_MSG_ID_SET_MODE: {
424  mavlink_set_mode_t mode;
425  mavlink_msg_set_mode_decode(msg, &mode);
426  if (mode.target_system == AC_ID) {
427  MAVLINK_DEBUG("got SET_MODE: base_mode:%d\n", mode.base_mode);
428  if (mode.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
430  }
431  else {
433  }
434  if (mode.base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
436  }
437  else if (mode.base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
439  }
440  }
441  break;
442  }
443 
444  case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: {
445  mavlink_set_position_target_local_ned_t target;
446  mavlink_msg_set_position_target_local_ned_decode(msg, &target);
447  // Check if this message is for this system
448  if (target.target_system == AC_ID) {
449  MAVLINK_DEBUG("SET_POSITION_TARGET_LOCAL_NED, byte_mask: %d\n", target.type_mask);
450  /* if position and yaw bits are not set to ignored, use only position for now */
451  if (!(target.type_mask & 0b1110000000100000)) {
452  switch (target.coordinate_frame) {
453  case MAV_FRAME_LOCAL_NED:
454  MAVLINK_DEBUG("set position target, frame LOCAL_NED\n");
456  break;
457  case MAV_FRAME_LOCAL_OFFSET_NED:
458  MAVLINK_DEBUG("set position target, frame LOCAL_OFFSET_NED\n");
460  break;
461  case MAV_FRAME_BODY_OFFSET_NED:
462  MAVLINK_DEBUG("set position target, frame BODY_OFFSET_NED\n");
464  break;
465  default:
466  break;
467  }
468  }
469  else if (!(target.type_mask & 0b0001110000100000)) {
470  /* position is set to ignore, but velocity not */
471  switch (target.coordinate_frame) {
472  case MAV_FRAME_LOCAL_NED:
473  MAVLINK_DEBUG("set velocity target, frame LOCAL_NED\n");
475  break;
476  default:
477  break;
478  }
479  }
480  }
481  break;
482  }
483 #endif
484 
485  default:
486  //Do nothing
487  MAVLINK_DEBUG("Received message with id: %d\r\n", msg->msgid);
488  break;
489  }
490 }
491 
492 /* ignore the unused-parameter warnings */
493 #pragma GCC diagnostic push
494 #pragma GCC diagnostic ignored "-Wunused-parameter"
495 
499 static void mavlink_send_heartbeat(struct transport_tx *trans, struct link_device *dev)
500 {
501  uint8_t mav_state = MAV_STATE_CALIBRATING;
502  uint8_t mav_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; // Ardupilot custom mode enabled
503  uint32_t custom_mode = 0;
504 #if defined(FIXEDWING_FIRMWARE)
505  uint8_t mav_type = MAV_TYPE_FIXED_WING;
506  switch (autopilot_get_mode()) {
507  case AP_MODE_MANUAL:
508  mav_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
509  break;
510  case AP_MODE_AUTO1:
511  mav_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
512  break;
513  case AP_MODE_AUTO2:
514  mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
515  break;
516  case AP_MODE_HOME:
517  mav_mode |= MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED;
518  break;
519  default:
520  break;
521  }
522 #elif defined(ROTORCRAFT_FIRMWARE)
523  uint8_t mav_type = MAV_TYPE_QUADROTOR;
524  switch (autopilot_get_mode()) {
525  case AP_MODE_HOME:
526  mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
527  break;
528  case AP_MODE_RATE_DIRECT:
530  case AP_MODE_RATE_Z_HOLD:
531  case AP_MODE_RC_DIRECT:
532  mav_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
533  break;
539  case AP_MODE_HOVER_CLIMB:
542  mav_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
543  break;
544  case AP_MODE_NAV:
545  mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
546  custom_mode = PLANE_MODE_GUIDED;
547  break;
548  case AP_MODE_GUIDED:
549  mav_mode = MAV_MODE_FLAG_GUIDED_ENABLED;
550  custom_mode = PLANE_MODE_GUIDED;
551  default:
552  break;
553  }
554 #else
555 #error "mavlink datalink: unsupported firmware"
556 #endif
557  if (stateIsAttitudeValid()) {
559  mav_state = MAV_STATE_STANDBY;
560  } else {
561  mav_state = MAV_STATE_ACTIVE;
562  mav_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
563  }
564  }
565  mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
566  mav_type,
568  mav_mode,
569  custom_mode,
570  mav_state);
572 }
573 
574 /*
575  * Send extended system state
576 */
577 static void mavlink_send_extended_sys_state(struct transport_tx *trans, struct link_device *dev) {
578  uint8_t landed_state = autopilot_in_flight()? MAV_LANDED_STATE_IN_AIR : MAV_LANDED_STATE_ON_GROUND;
579  mavlink_msg_extended_sys_state_send(MAVLINK_COMM_0, MAV_VTOL_STATE_UNDEFINED, landed_state);
581 }
582 
586 static void mavlink_send_sys_status(struct transport_tx *trans, struct link_device *dev)
587 {
589 #define UAV_SENSORS (MAV_SYS_STATUS_SENSOR_3D_GYRO|MAV_SYS_STATUS_SENSOR_3D_ACCEL|MAV_SYS_STATUS_SENSOR_3D_MAG|MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE)
590 
591  mavlink_msg_sys_status_send(MAVLINK_COMM_0,
592  UAV_SENSORS, // On-board sensors: present (bitmap)
593  UAV_SENSORS, // On-board sensors: active (bitmap)
594  UAV_SENSORS, // On-board sensors: state (bitmap)
595  -1,//10*sys_mon.cpu_load, // System loadof main-loop time (0=0% to 1000=100%)
596  electrical.vsupply * 1000.f, // Battery voltage (milivolts)
597  electrical.current * 100.f, // Battery current (10x miliampere)
598  -1, // Battery remaining (0-100 in %)
599  0, // Communication packet drops (0=0% to 10000=100%)
600  0, // Communication error(per packet) (0=0% to 10000=100%)
601  0, // Autopilot specific error 1
602  0, // Autopilot specific error 2
603  0, // Autopilot specific error 3
604  0, // Autopilot specific error 4
605  0,
606  0,
607  0);
609 }
610 
616 static void mavlink_send_system_time(struct transport_tx *trans, struct link_device *dev)
617 {
618  mavlink_msg_system_time_send(MAVLINK_COMM_0, 0, get_sys_time_msec());
620 }
621 
625 static void mavlink_send_attitude(struct transport_tx *trans, struct link_device *dev)
626 {
627  mavlink_msg_attitude_send(MAVLINK_COMM_0,
629  stateGetNedToBodyEulers_f()->phi, // Phi
630  stateGetNedToBodyEulers_f()->theta, // Theta
631  stateGetNedToBodyEulers_f()->psi, // Psi
632  stateGetBodyRates_f()->p, // p
633  stateGetBodyRates_f()->q, // q
634  stateGetBodyRates_f()->r); // r
636 }
637 
638 static void mavlink_send_local_position_ned(struct transport_tx *trans, struct link_device *dev)
639 {
640  mavlink_msg_local_position_ned_send(MAVLINK_COMM_0,
645  stateGetSpeedNed_f()->x,
646  stateGetSpeedNed_f()->y,
647  stateGetSpeedNed_f()->z);
649 }
650 
651 static void mavlink_send_global_position_int(struct transport_tx *trans, struct link_device *dev)
652 {
653  float heading = DegOfRad(stateGetNedToBodyEulers_f()->psi);
654  if (heading < 0.) {
655  heading += 360;
656  }
657  uint16_t compass_heading = heading * 100;
659  int32_t hmsl_alt = stateGetHmslOrigin_i() - stateGetNedOrigin_i()->alt;
661  mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
665  stateGetPositionLla_i()->alt + hmsl_alt,
666  relative_alt,
667  stateGetSpeedNed_f()->x * 100,
668  stateGetSpeedNed_f()->y * 100,
669  stateGetSpeedNed_f()->z * 100,
670  compass_heading);
672 }
673 
674 static void mavlink_send_gps_global_origin(struct transport_tx *trans, struct link_device *dev)
675 {
676  if (state.ned_initialized_i) {
677  mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0,
683  }
684 }
685 
689 static void mavlink_send_params(struct transport_tx *trans, struct link_device *dev)
690 {
691  if (mavlink_params_idx >= NB_SETTING) {
692  return;
693  }
694 
695  mavlink_msg_param_value_send(MAVLINK_COMM_0,
697  settings_get_value(mavlink_params_idx),
698  MAV_PARAM_TYPE_REAL32,
699  NB_SETTING,
702 
704 }
705 
706 static void mavlink_send_autopilot_version(struct transport_tx *trans, struct link_device *dev)
707 {
709  static uint32_t ver = PPRZ_VERSION_INT;
710  static uint64_t sha;
711  get_pprz_git_version((uint8_t *)&sha);
712  mavlink_msg_autopilot_version_send(MAVLINK_COMM_0,
713  18446744073709551615U, //uint64_t capabilities,
714  ver, //uint32_t flight_sw_version,
715  0, //uint32_t middleware_sw_version,
716  0, //uint32_t os_sw_version,
717  0, //uint32_t board_version,
718  0, //const uint8_t *flight_custom_version,
719  0, //const uint8_t *middleware_custom_version,
720  0, //const uint8_t *os_custom_version,
721  0, //uint16_t vendor_id,
722  0, //uint16_t product_id,
723  sha, //uint64_t uid
724  0);
726 }
727 
728 static void mavlink_send_attitude_quaternion(struct transport_tx *trans, struct link_device *dev)
729 {
730  float repr_offset_q[4] = {0, 0, 0, 0};
731  mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_0,
738  stateGetBodyRates_f()->q,
739  stateGetBodyRates_f()->r,
740  repr_offset_q);
742 }
743 
744 #if USE_GPS
745 #include "modules/gps/gps.h"
746 #endif
747 
748 static void mavlink_send_gps_raw_int(struct transport_tx *trans, struct link_device *dev)
749 {
750 #if USE_GPS
751  int32_t course = DegOfRad(gps.course) / 1e5;
752  if (course < 0) {
753  course += 36000;
754  }
755  mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
757  gps.fix,
758  gps.lla_pos.lat,
759  gps.lla_pos.lon,
760  gps.hmsl,
761  gps.pdop,
762  UINT16_MAX, // VDOP
763  gps.gspeed,
764  course,
765  gps.num_sv,
766  gps.lla_pos.alt,
767  gps.hacc,
768  gps.vacc,
769  gps.sacc,
770  0,
771  0);
773 #endif
774 }
775 
786 static void mavlink_send_gps_status(struct transport_tx *trans, struct link_device *dev)
787 {
788 #if USE_GPS
789  uint8_t nb_sats = Min(GPS_NB_CHANNELS, 20);
790  uint8_t prn[20];
791  uint8_t used[20];
792  uint8_t elevation[20];
793  uint8_t azimuth[20];
794  uint8_t snr[20];
795  for (uint8_t i = 0; i < nb_sats; i++) {
796  prn[i] = gps.svinfos[i].svid;
797  // set sat as used if cno > 0, not quite true though
798  if (gps.svinfos[i].cno > 0) {
799  used[i] = 1;
800  }
801  elevation[i] = gps.svinfos[i].elev;
802  // convert azimuth to unsigned representation: 0: 0 deg, 255: 360 deg.
803  uint8_t azim;
804  if (gps.svinfos[i].azim < 0) {
805  azim = (float)(-gps.svinfos[i].azim + 180) / 360 * 255;
806  } else {
807  azim = (float)gps.svinfos[i].azim / 360 * 255;
808  }
809  azimuth[i] = azim;
810  }
811  mavlink_msg_gps_status_send(MAVLINK_COMM_0,
812  gps.num_sv, prn, used, elevation, azimuth, snr);
814 #endif
815 }
816 
817 #if defined RADIO_CONTROL
819 // since they really want PPM values, use a hack to check if are using ppm subsystem
820 #ifdef PPM_PULSE_TYPE_POSITIVE
821 #define RC_CHANNELS RADIO_CTL_NB
823 #define PPM_PULSES(_i) ((_i) < RADIO_CTL_NB ? ppm_pulses[(_i)] : UINT16_MAX)
824 #else
825 // use radio_control.values for now...
826 #define RC_CHANNELS RADIO_CONTROL_NB_CHANNEL
827 #define PPM_OF_PPRZ(_v) ((_v) / 19.2 + 1500)
828 #define PPM_PULSES(_i) ((_i) < RADIO_CONTROL_NB_CHANNEL ? PPM_OF_PPRZ(radio_control.values[(_i)]) + MAX_PPRZ : UINT16_MAX)
829 #endif
830 #endif
831 
832 static void mavlink_send_rc_channels(struct transport_tx *trans, struct link_device *dev)
833 {
834 #if defined RADIO_CONTROL
835  mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
837  RC_CHANNELS,
838  PPM_PULSES(0), PPM_PULSES(1), PPM_PULSES(2),
839  PPM_PULSES(3), PPM_PULSES(4), PPM_PULSES(5),
840  PPM_PULSES(6), PPM_PULSES(7), PPM_PULSES(8),
841  PPM_PULSES(9), PPM_PULSES(10), PPM_PULSES(11),
842  PPM_PULSES(12), PPM_PULSES(13), PPM_PULSES(14),
843  PPM_PULSES(15), PPM_PULSES(16), PPM_PULSES(17),
844  255); // rssi unknown
845 #else
846  mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
848  0, // zero channels available
849  UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
850  UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
851  UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
852  UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
853  UINT16_MAX, UINT16_MAX, 255);
854 #endif
856 }
857 
859 static void mavlink_send_battery_status(struct transport_tx *trans, struct link_device *dev)
860 {
861  static uint16_t voltages[14] = {0};
862  // we simply only set one cell for now
863  voltages[0] = electrical.vsupply * 1000.f; // convert to mV
865  mavlink_msg_battery_status_send(MAVLINK_COMM_0,
866  0, // id
867  0, // battery_function
868  0, // type
869  INT16_MAX, // unknown temperature
870  voltages, // cell voltages
871  electrical.current * 100.f, // convert to deciA
872  electrical.charge * 1000.f, // convert to mAh
873  electrical.energy * 36, // convert to hecto Joule
874  -1, // remaining percentage not estimated
875  0,
876  MAV_BATTERY_CHARGE_STATE_UNDEFINED,
877  &voltages[10],
878  MAV_BATTERY_MODE_UNKNOWN,
879  0);
881 }
882 
883 #include "modules/core/commands.h"
887 static void mavlink_send_vfr_hud(struct transport_tx *trans, struct link_device *dev)
888 {
889  /* Current heading in degrees, in compass units (0..360, 0=north) */
890  int16_t heading = DegOfRad(stateGetNedToBodyEulers_f()->psi);
891  /* Current throttle setting in integer percent, 0 to 100 */
892  // is a 16bit unsigned int but supposed to be from 0 to 100??
893  uint16_t throttle;
894 #ifdef COMMAND_THRUST
895  throttle = commands[COMMAND_THRUST] / (MAX_PPRZ / 100);
896 #elif defined COMMAND_THROTTLE
897  throttle = commands[COMMAND_THROTTLE] / (MAX_PPRZ / 100);
898 #endif
899  float hmsl_alt = stateGetHmslOrigin_f() - stateGetLlaOrigin_f().alt;
900  mavlink_msg_vfr_hud_send(MAVLINK_COMM_0,
901  Max(0,stateGetAirspeed_f()),
902  stateGetHorizontalSpeedNorm_f(), // groundspeed
903  heading,
904  throttle,
905  stateGetPositionLla_f()->alt + hmsl_alt,
906  stateGetSpeedNed_f()->z); // climb rate
908 }
909 
910 /* end ignore unused-paramter */
911 #pragma GCC diagnostic pop
static int16_t course[3]
Definition: airspeed_uADC.c:58
bool autopilot_set_mode(uint8_t new_autopilot_mode)
set autopilot mode
Definition: autopilot.c:193
uint8_t autopilot_get_mode(void)
get autopilot mode
Definition: autopilot.c:222
bool autopilot_set_motors_on(bool motors_on)
turn motors on/off, eventually depending of the current mode set kill_throttle accordingly FIXME is i...
Definition: autopilot.c:250
bool autopilot_get_motors_on(void)
get motors status
Definition: autopilot.c:295
bool autopilot_in_flight(void)
get in_flight flag
Definition: autopilot.c:340
bool autopilot_throttle_killed(void)
get kill status
Definition: autopilot.c:313
Core autopilot interface common to all firmwares.
bool autopilot_guided_move_ned(float vx, float vy, float vz, float heading)
Set velocity and heading setpoints in GUIDED mode.
bool autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw)
Set position and heading setpoints wrt.
bool autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw)
Set position and heading setpoints wrt.
bool autopilot_guided_goto_ned(float x, float y, float z, float heading)
Set position and heading setpoints in GUIDED mode.
Autopilot guided mode interface.
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
Definition: sys_time_arch.c:71
uint32_t get_sys_time_msec(void)
Get the time in milliseconds since startup.
Definition: sys_time_arch.c:98
pprz_t commands[COMMANDS_NB]
Definition: commands.c:30
Hardware independent code for commands handling.
struct Electrical electrical
Definition: electrical.c:92
Interface for electrical status: supply voltage, current, battery status, etc.
float energy
consumed energy in Wh
Definition: electrical.h:49
float current
current in A
Definition: electrical.h:47
float charge
consumed electric charge in Ah
Definition: electrical.h:48
float vsupply
supply voltage in V
Definition: electrical.h:45
#define Min(x, y)
Definition: esc_dshot.c:109
#define AP_MODE_HOME
#define AP_MODE_MANUAL
AP modes.
#define AP_MODE_AUTO2
#define AP_MODE_AUTO1
struct GpsState gps
global GPS state
Definition: gps.c:74
Device independent GPS code (interface)
int16_t azim
azimuth in deg
Definition: gps.h:83
int32_t hmsl
height above mean sea level (MSL) in mm
Definition: gps.h:94
int8_t elev
elevation in deg
Definition: gps.h:82
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
Definition: gps.h:92
uint32_t sacc
speed accuracy in cm/s
Definition: gps.h:103
int32_t course
GPS course over ground in rad*1e7, [0, 2*Pi]*1e7 (CW/north)
Definition: gps.h:99
uint8_t cno
Carrier to Noise Ratio (Signal Strength) in dbHz.
Definition: gps.h:81
uint32_t hacc
horizontal accuracy in cm
Definition: gps.h:101
#define GPS_NB_CHANNELS
Definition: gps.h:57
uint16_t pdop
position dilution of precision scaled by 100
Definition: gps.h:105
uint8_t svid
Satellite ID.
Definition: gps.h:78
uint16_t gspeed
norm of 2d ground speed in cm/s
Definition: gps.h:97
uint32_t vacc
vertical accuracy in cm
Definition: gps.h:102
struct SVinfo svinfos[GPS_NB_CHANNELS]
holds information from the Space Vehicles (Satellites)
Definition: gps.h:112
uint8_t num_sv
number of sat in fix
Definition: gps.h:106
uint8_t fix
status of fix
Definition: gps.h:107
int32_t lat
in degrees*1e7
int32_t alt
in millimeters above WGS84 reference ellipsoid
int32_t lon
in degrees*1e7
void ned_of_lla_point_i(struct NedCoor_i *ned, struct LtpDef_i *def, struct LlaCoor_i *lla)
Convert a point from LLA to local NED.
#define MM_OF_M(_m)
vector in Latitude, Longitude and Altitude
vector in North East Down coordinates
static bool stateIsAttitudeValid(void)
Test if attitudes are valid.
Definition: state.h:1224
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition: state.h:1306
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
Definition: state.h:1294
struct State state
Definition: state.c:36
static struct LlaCoor_i * stateGetPositionLla_i(void)
Get position in LLA coordinates (int).
Definition: state.h:812
bool ned_initialized_i
true if local int coordinate frame is initialsed
Definition: state.h:199
static struct LtpDef_i * stateGetNedOrigin_i(void)
Get the coordinate NED frame origin (int)
Definition: state.h:556
int32_t stateGetHmslOrigin_i(void)
Get the HMSL of the frame origin (int)
Definition: state.c:190
float stateGetHmslOrigin_f(void)
Get the HMSL of the frame origin (float)
Definition: state.c:204
static struct LlaCoor_f * stateGetPositionLla_f(void)
Get position in LLA coordinates (float).
Definition: state.h:857
static struct NedCoor_f * stateGetPositionNed_f(void)
Get position in local NED coordinates (float).
Definition: state.h:839
struct LlaCoor_i stateGetLlaOrigin_i(void)
Get the LLA position of the frame origin (int)
Definition: state.c:124
struct LlaCoor_f stateGetLlaOrigin_f(void)
Get the LLA position of the frame origin (float)
Definition: state.c:143
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
Definition: state.h:1367
static float stateGetHorizontalSpeedNorm_f(void)
Get norm of horizontal ground speed (float).
Definition: state.h:1076
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
Definition: state.h:1049
static float stateGetAirspeed_f(void)
Get airspeed (float).
Definition: state.h:1590
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
static float p[2][2]
void mavlink_mission_init(mavlink_mission_mgr *mgr)
void mavlink_mission_message_handler(const mavlink_message_t *msg)
void mavlink_mission_periodic(void)
update current block and send if changed
Common functions used within the mission library, blocks and waypoints cannot be send simultaneously ...
void waypoint_set_latlon(uint8_t wp_id, struct LlaCoor_i *lla)
set waypoint latitude/longitude without updating altitude
Definition: waypoints.c:273
void waypoint_set_alt(uint8_t wp_id, float alt)
Set altitude of waypoint in meters (above reference)
Definition: waypoints.c:233
static uint32_t idx
uint8_t status
#define MAX_PPRZ
Definition: paparazzi.h:8
float alt
in meters (normally above WGS84 reference ellipsoid)
Generic interface for radio control modules.
#define AP_MODE_HOVER_DIRECT
#define AP_MODE_RATE_DIRECT
#define AP_MODE_RATE_RC_CLIMB
#define AP_MODE_HOVER_CLIMB
#define AP_MODE_HOVER_Z_HOLD
#define AP_MODE_RC_DIRECT
#define AP_MODE_ATTITUDE_DIRECT
#define AP_MODE_ATTITUDE_CLIMB
#define AP_MODE_NAV
#define AP_MODE_GUIDED
#define AP_MODE_ATTITUDE_Z_HOLD
#define AP_MODE_ATTITUDE_RC_CLIMB
#define AP_MODE_RATE_Z_HOLD
#define AP_MODE_CARE_FREE_DIRECT
static uint8_t mode
mode holds the current sonar mode mode = 0 used at high altitude, uses 16 wave patterns mode = 1 used...
Definition: sonar_bebop.c:65
API to get/set the generic vehicle states.
#define TRUE
Definition: std.h:4
#define FALSE
Definition: std.h:5
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:74
Architecture independent timing functions.
struct target_t target
Definition: target_pos.c:65
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition: telemetry.c:51
Common tools for periodic telemetry interface Allows subsystem to register callback functions.
Periodic telemetry structure.
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
Definition: vl53l1_types.h:88
int int32_t
Typedef defining 32 bit int type.
Definition: vl53l1_types.h:83
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
Definition: vl53l1_types.h:78
short int16_t
Typedef defining 16 bit short type.
Definition: vl53l1_types.h:93
unsigned long long uint64_t
Definition: vl53l1_types.h:72
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
Definition: vl53l1_types.h:98
signed char int8_t
Typedef defining 8 bit char type.
Definition: vl53l1_types.h:103
float heading
Definition: wedgebug.c:258