PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_receiver.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2019 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 /**
35  * @file mavlink_receiver.cpp
36  * MAVLink protocol message receive and dispatch
37  *
38  * @author Lorenz Meier <lorenz@px4.io>
39  * @author Anton Babushkin <anton@px4.io>
40  * @author Thomas Gubler <thomas@px4.io>
41  */
42 
43 #include <airspeed/airspeed.h>
45 #include <conversion/rotation.h>
46 #include <drivers/drv_rc_input.h>
47 #include <drivers/drv_tone_alarm.h>
48 #include <ecl/geo/geo.h>
49 #include <systemlib/px4_macros.h>
50 
51 #ifdef CONFIG_NET
52 #include <net/if.h>
53 #include <arpa/inet.h>
54 #include <netinet/in.h>
55 #endif
56 
57 #ifdef __PX4_DARWIN
58 #include <sys/param.h>
59 #include <sys/mount.h>
60 #else
61 #include <sys/statfs.h>
62 #endif
63 
64 #ifndef __PX4_POSIX
65 #include <termios.h>
66 #endif
67 
68 #include "mavlink_command_sender.h"
69 #include "mavlink_main.h"
70 #include "mavlink_receiver.h"
71 
72 #ifdef CONFIG_NET
73 #define MAVLINK_RECEIVER_NET_ADDED_STACK 1360
74 #else
75 #define MAVLINK_RECEIVER_NET_ADDED_STACK 0
76 #endif
77 
78 using matrix::wrap_2pi;
79 
81  ModuleParams(nullptr),
82  _mavlink(parent),
83  _mavlink_ftp(parent),
84  _mavlink_log_handler(parent),
85  _mission_manager(parent),
86  _parameters_manager(parent),
87  _mavlink_timesync(parent)
88 {
89 }
90 
91 void
92 MavlinkReceiver::acknowledge(uint8_t sysid, uint8_t compid, uint16_t command, uint8_t result)
93 {
94  vehicle_command_ack_s command_ack{};
95 
96  command_ack.timestamp = hrt_absolute_time();
97  command_ack.command = command;
98  command_ack.result = result;
99  command_ack.target_system = sysid;
100  command_ack.target_component = compid;
101 
102  _cmd_ack_pub.publish(command_ack);
103 }
104 
105 void
107 {
108  switch (msg->msgid) {
109  case MAVLINK_MSG_ID_COMMAND_LONG:
111  break;
112 
113  case MAVLINK_MSG_ID_COMMAND_INT:
115  break;
116 
117  case MAVLINK_MSG_ID_COMMAND_ACK:
119  break;
120 
121  case MAVLINK_MSG_ID_OPTICAL_FLOW_RAD:
123  break;
124 
125  case MAVLINK_MSG_ID_PING:
126  handle_message_ping(msg);
127  break;
128 
129  case MAVLINK_MSG_ID_SET_MODE:
131  break;
132 
133  case MAVLINK_MSG_ID_ATT_POS_MOCAP:
135  break;
136 
137  case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
139  break;
140 
141  case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
143  break;
144 
145  case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
147  break;
148 
149  case MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET:
151  break;
152 
153  case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
155  break;
156 
157  case MAVLINK_MSG_ID_ODOMETRY:
159  break;
160 
161  case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
163  break;
164 
165  case MAVLINK_MSG_ID_RADIO_STATUS:
167  break;
168 
169  case MAVLINK_MSG_ID_MANUAL_CONTROL:
171  break;
172 
173  case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
175  break;
176 
177  case MAVLINK_MSG_ID_HEARTBEAT:
179  break;
180 
181  case MAVLINK_MSG_ID_DISTANCE_SENSOR:
183  break;
184 
185  case MAVLINK_MSG_ID_FOLLOW_TARGET:
187  break;
188 
189  case MAVLINK_MSG_ID_LANDING_TARGET:
191  break;
192 
193  case MAVLINK_MSG_ID_CELLULAR_STATUS:
195  break;
196 
197  case MAVLINK_MSG_ID_ADSB_VEHICLE:
199  break;
200 
201  case MAVLINK_MSG_ID_UTM_GLOBAL_POSITION:
203  break;
204 
205  case MAVLINK_MSG_ID_COLLISION:
207  break;
208 
209  case MAVLINK_MSG_ID_GPS_RTCM_DATA:
211  break;
212 
213  case MAVLINK_MSG_ID_BATTERY_STATUS:
215  break;
216 
217  case MAVLINK_MSG_ID_SERIAL_CONTROL:
219  break;
220 
221  case MAVLINK_MSG_ID_LOGGING_ACK:
223  break;
224 
225  case MAVLINK_MSG_ID_PLAY_TUNE:
227  break;
228 
229  case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
231  break;
232 
233  case MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS:
235  break;
236 
237  case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
239  break;
240 
241  case MAVLINK_MSG_ID_DEBUG:
243  break;
244 
245  case MAVLINK_MSG_ID_DEBUG_VECT:
247  break;
248 
249  case MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY:
251  break;
252 
253  case MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS:
255  break;
256 
257  case MAVLINK_MSG_ID_STATUSTEXT:
259  break;
260 
261  default:
262  break;
263  }
264 
265  /*
266  * Only decode hil messages in HIL mode.
267  *
268  * The HIL mode is enabled by the HIL bit flag
269  * in the system mode. Either send a set mode
270  * COMMAND_LONG message or a SET_MODE message
271  *
272  * Accept HIL GPS messages if use_hil_gps flag is true.
273  * This allows to provide fake gps measurements to the system.
274  */
275  if (_mavlink->get_hil_enabled()) {
276  switch (msg->msgid) {
277  case MAVLINK_MSG_ID_HIL_SENSOR:
279  break;
280 
281  case MAVLINK_MSG_ID_HIL_STATE_QUATERNION:
283  break;
284 
285  case MAVLINK_MSG_ID_HIL_OPTICAL_FLOW:
287  break;
288 
289  default:
290  break;
291  }
292  }
293 
294 
295  if (_mavlink->get_hil_enabled() || (_mavlink->get_use_hil_gps() && msg->sysid == mavlink_system.sysid)) {
296  switch (msg->msgid) {
297  case MAVLINK_MSG_ID_HIL_GPS:
299  break;
300 
301  default:
302  break;
303  }
304 
305  }
306 
307  /* If we've received a valid message, mark the flag indicating so.
308  This is used in the '-w' command-line flag. */
310 }
311 
312 bool
313 MavlinkReceiver::evaluate_target_ok(int command, int target_system, int target_component)
314 {
315  /* evaluate if this system should accept this command */
316  bool target_ok = false;
317 
318  switch (command) {
319 
320  case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
321  case MAV_CMD_REQUEST_PROTOCOL_VERSION:
322  /* broadcast and ignore component */
323  target_ok = (target_system == 0) || (target_system == mavlink_system.sysid);
324  break;
325 
326  default:
327  target_ok = (target_system == mavlink_system.sysid) && ((target_component == mavlink_system.compid)
328  || (target_component == MAV_COMP_ID_ALL));
329  break;
330  }
331 
332  return target_ok;
333 }
334 
335 void
337 {
338  mavlink_flight_information_t flight_info{};
339  flight_info.flight_uuid = static_cast<uint64_t>(_param_com_flight_uuid.get());
340 
341  actuator_armed_s actuator_armed{};
342  bool ret = _actuator_armed_sub.copy(&actuator_armed);
343 
344  if (ret && actuator_armed.timestamp != 0) {
345  flight_info.arming_time_utc = flight_info.takeoff_time_utc = actuator_armed.armed_time_ms;
346  }
347 
348  flight_info.time_boot_ms = hrt_absolute_time() / 1000;
349  mavlink_msg_flight_information_send_struct(_mavlink->get_channel(), &flight_info);
350 }
351 
352 void
354 {
355  mavlink_storage_information_t storage_info{};
356  const char *microsd_dir = PX4_STORAGEDIR;
357 
358  if (storage_id == 0 || storage_id == 1) { // request is for all or the first storage
359  storage_info.storage_id = 1;
360 
361  struct statfs statfs_buf;
362  uint64_t total_bytes = 0;
363  uint64_t avail_bytes = 0;
364 
365  if (statfs(microsd_dir, &statfs_buf) == 0) {
366  total_bytes = (uint64_t)statfs_buf.f_blocks * statfs_buf.f_bsize;
367  avail_bytes = (uint64_t)statfs_buf.f_bavail * statfs_buf.f_bsize;
368  }
369 
370  if (total_bytes == 0) { // on NuttX we get 0 total bytes if no SD card is inserted
371  storage_info.storage_count = 0;
372  storage_info.status = 0; // not available
373 
374  } else {
375  storage_info.storage_count = 1;
376  storage_info.status = 2; // available & formatted
377  storage_info.total_capacity = total_bytes / 1024. / 1024.;
378  storage_info.available_capacity = avail_bytes / 1024. / 1024.;
379  storage_info.used_capacity = (total_bytes - avail_bytes) / 1024. / 1024.;
380  }
381 
382  } else {
383  // only one storage supported
384  storage_info.storage_id = storage_id;
385  storage_info.storage_count = 1;
386  }
387 
388  storage_info.time_boot_ms = hrt_absolute_time() / 1000;
389  mavlink_msg_storage_information_send_struct(_mavlink->get_channel(), &storage_info);
390 }
391 
392 void
394 {
395  /* command */
396  mavlink_command_long_t cmd_mavlink;
397  mavlink_msg_command_long_decode(msg, &cmd_mavlink);
398 
399  vehicle_command_s vcmd{};
400 
401  vcmd.timestamp = hrt_absolute_time();
402 
403  /* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
404  vcmd.param1 = cmd_mavlink.param1;
405  vcmd.param2 = cmd_mavlink.param2;
406  vcmd.param3 = cmd_mavlink.param3;
407  vcmd.param4 = cmd_mavlink.param4;
408  vcmd.param5 = (double)cmd_mavlink.param5;
409  vcmd.param6 = (double)cmd_mavlink.param6;
410  vcmd.param7 = cmd_mavlink.param7;
411  vcmd.command = cmd_mavlink.command;
412  vcmd.target_system = cmd_mavlink.target_system;
413  vcmd.target_component = cmd_mavlink.target_component;
414  vcmd.source_system = msg->sysid;
415  vcmd.source_component = msg->compid;
416  vcmd.confirmation = cmd_mavlink.confirmation;
417  vcmd.from_external = true;
418 
419  handle_message_command_both(msg, cmd_mavlink, vcmd);
420 }
421 
422 void
424 {
425  /* command */
426  mavlink_command_int_t cmd_mavlink;
427  mavlink_msg_command_int_decode(msg, &cmd_mavlink);
428 
429  vehicle_command_s vcmd{};
430  vcmd.timestamp = hrt_absolute_time();
431 
432  /* Copy the content of mavlink_command_int_t cmd_mavlink into command_t cmd */
433  vcmd.param1 = cmd_mavlink.param1;
434  vcmd.param2 = cmd_mavlink.param2;
435  vcmd.param3 = cmd_mavlink.param3;
436  vcmd.param4 = cmd_mavlink.param4;
437  vcmd.param5 = ((double)cmd_mavlink.x) / 1e7;
438  vcmd.param6 = ((double)cmd_mavlink.y) / 1e7;
439  vcmd.param7 = cmd_mavlink.z;
440  vcmd.command = cmd_mavlink.command;
441  vcmd.target_system = cmd_mavlink.target_system;
442  vcmd.target_component = cmd_mavlink.target_component;
443  vcmd.source_system = msg->sysid;
444  vcmd.source_component = msg->compid;
445  vcmd.confirmation = false;
446  vcmd.from_external = true;
447 
448  handle_message_command_both(msg, cmd_mavlink, vcmd);
449 }
450 
451 template <class T>
452 void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const T &cmd_mavlink,
453  const vehicle_command_s &vehicle_command)
454 {
455  bool target_ok = evaluate_target_ok(cmd_mavlink.command, cmd_mavlink.target_system, cmd_mavlink.target_component);
456 
457  bool send_ack = true;
458  uint8_t result = vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED;
459 
460  if (!target_ok) {
461  acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, vehicle_command_ack_s::VEHICLE_RESULT_FAILED);
462  return;
463  }
464 
465  if (cmd_mavlink.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
466  /* send autopilot version message */
468 
469  } else if (cmd_mavlink.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
470  /* send protocol version message */
472 
473  } else if (cmd_mavlink.command == MAV_CMD_GET_HOME_POSITION) {
474  _mavlink->configure_stream_threadsafe("HOME_POSITION", 0.5f);
475 
476  } else if (cmd_mavlink.command == MAV_CMD_SET_MESSAGE_INTERVAL) {
477  if (set_message_interval((int)(cmd_mavlink.param1 + 0.5f), cmd_mavlink.param2, cmd_mavlink.param3)) {
478  result = vehicle_command_ack_s::VEHICLE_RESULT_FAILED;
479  }
480 
481  } else if (cmd_mavlink.command == MAV_CMD_GET_MESSAGE_INTERVAL) {
482  get_message_interval((int)cmd_mavlink.param1);
483 
484  } else if (cmd_mavlink.command == MAV_CMD_REQUEST_FLIGHT_INFORMATION) {
486 
487  } else if (cmd_mavlink.command == MAV_CMD_REQUEST_STORAGE_INFORMATION) {
488  if ((int)(cmd_mavlink.param2 + 0.5f) == 1) {
489  send_storage_information(cmd_mavlink.param1 + 0.5f);
490  }
491 
492  } else {
493 
494  send_ack = false;
495 
496  if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) {
497  PX4_WARN("ignoring CMD with same SYS/COMP (%d/%d) ID", mavlink_system.sysid, mavlink_system.compid);
498  return;
499  }
500 
501  if (cmd_mavlink.command == MAV_CMD_LOGGING_START) {
502  // check that we have enough bandwidth available: this is given by the configured logger topics
503  // and rates. The 5000 is somewhat arbitrary, but makes sure that we cannot enable log streaming
504  // on a radio link
505  if (_mavlink->get_data_rate() < 5000) {
506  send_ack = true;
507  result = vehicle_command_ack_s::VEHICLE_RESULT_DENIED;
508  _mavlink->send_statustext_critical("Not enough bandwidth to enable log streaming");
509 
510  } else {
511  // we already instanciate the streaming object, because at this point we know on which
512  // mavlink channel streaming was requested. But in fact it's possible that the logger is
513  // not even running. The main mavlink thread takes care of this by waiting for an ack
514  // from the logger.
515  _mavlink->try_start_ulog_streaming(msg->sysid, msg->compid);
516  }
517 
518  } else if (cmd_mavlink.command == MAV_CMD_LOGGING_STOP) {
520  }
521 
522  if (!send_ack) {
523  _cmd_pub.publish(vehicle_command);
524  }
525  }
526 
527  if (send_ack) {
528  acknowledge(msg->sysid, msg->compid, cmd_mavlink.command, result);
529  }
530 }
531 
532 void
534 {
535  mavlink_command_ack_t ack;
536  mavlink_msg_command_ack_decode(msg, &ack);
537 
539 
540  vehicle_command_ack_s command_ack{};
541 
542  command_ack.timestamp = hrt_absolute_time();
543  command_ack.result_param2 = ack.result_param2;
544  command_ack.command = ack.command;
545  command_ack.result = ack.result;
546  command_ack.from_external = true;
547  command_ack.result_param1 = ack.progress;
548  command_ack.target_system = ack.target_system;
549  command_ack.target_component = ack.target_component;
550 
551  _cmd_ack_pub.publish(command_ack);
552 
553  // TODO: move it to the same place that sent the command
554  if (ack.result != MAV_RESULT_ACCEPTED && ack.result != MAV_RESULT_IN_PROGRESS) {
555  if (msg->compid == MAV_COMP_ID_CAMERA) {
556  PX4_WARN("Got unsuccessful result %d from camera", ack.result);
557  }
558  }
559 }
560 
561 void
563 {
564  /* optical flow */
565  mavlink_optical_flow_rad_t flow;
566  mavlink_msg_optical_flow_rad_decode(msg, &flow);
567 
568  optical_flow_s f{};
569 
570  f.timestamp = hrt_absolute_time();
571  f.time_since_last_sonar_update = flow.time_delta_distance_us;
572  f.integration_timespan = flow.integration_time_us;
573  f.pixel_flow_x_integral = flow.integrated_x;
574  f.pixel_flow_y_integral = flow.integrated_y;
575  f.gyro_x_rate_integral = flow.integrated_xgyro;
576  f.gyro_y_rate_integral = flow.integrated_ygyro;
577  f.gyro_z_rate_integral = flow.integrated_zgyro;
578  f.gyro_temperature = flow.temperature;
579  f.ground_distance_m = flow.distance;
580  f.quality = flow.quality;
581  f.sensor_id = flow.sensor_id;
582  f.max_flow_rate = _param_sens_flow_maxr.get();
583  f.min_ground_distance = _param_sens_flow_minhgt.get();
584  f.max_ground_distance = _param_sens_flow_maxhgt.get();
585 
586  /* read flow sensor parameters */
587  const Rotation flow_rot = (Rotation)_param_sens_flow_rot.get();
588 
589  /* rotate measurements according to parameter */
590  float zero_val = 0.0f;
591  rotate_3f(flow_rot, f.pixel_flow_x_integral, f.pixel_flow_y_integral, zero_val);
592  rotate_3f(flow_rot, f.gyro_x_rate_integral, f.gyro_y_rate_integral, f.gyro_z_rate_integral);
593 
595 
596  /* Use distance value for distance sensor topic */
597  if (flow.distance > 0.0f) { // negative values signal invalid data
598 
599  distance_sensor_s d{};
600 
601  d.timestamp = f.timestamp;
602  d.min_distance = 0.3f;
603  d.max_distance = 5.0f;
604  d.current_distance = flow.distance; /* both are in m */
605  d.type = 1;
606  d.id = distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND;
607  d.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
608  d.variance = 0.0;
609 
611  }
612 }
613 
614 void
616 {
617  /* optical flow */
618  mavlink_hil_optical_flow_t flow;
619  mavlink_msg_hil_optical_flow_decode(msg, &flow);
620 
621  optical_flow_s f{};
622 
623  f.timestamp = hrt_absolute_time(); // XXX we rely on the system time for now and not flow.time_usec;
624  f.integration_timespan = flow.integration_time_us;
625  f.pixel_flow_x_integral = flow.integrated_x;
626  f.pixel_flow_y_integral = flow.integrated_y;
627  f.gyro_x_rate_integral = flow.integrated_xgyro;
628  f.gyro_y_rate_integral = flow.integrated_ygyro;
629  f.gyro_z_rate_integral = flow.integrated_zgyro;
630  f.time_since_last_sonar_update = flow.time_delta_distance_us;
631  f.ground_distance_m = flow.distance;
632  f.quality = flow.quality;
633  f.sensor_id = flow.sensor_id;
634  f.gyro_temperature = flow.temperature;
635 
637 
638  /* Use distance value for distance sensor topic */
639  distance_sensor_s d{};
640 
642  d.min_distance = 0.3f;
643  d.max_distance = 5.0f;
644  d.current_distance = flow.distance; /* both are in m */
645  d.type = distance_sensor_s::MAV_DISTANCE_SENSOR_LASER;
646  d.id = 0;
647  d.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
648  d.variance = 0.0;
649 
651 }
652 
653 void
655 {
656  mavlink_set_mode_t new_mode;
657  mavlink_msg_set_mode_decode(msg, &new_mode);
658 
659  union px4_custom_mode custom_mode;
660  custom_mode.data = new_mode.custom_mode;
661 
662  vehicle_command_s vcmd{};
663 
664  vcmd.timestamp = hrt_absolute_time();
665 
666  /* copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
667  vcmd.param1 = (float)new_mode.base_mode;
668  vcmd.param2 = (float)custom_mode.main_mode;
669  vcmd.param3 = (float)custom_mode.sub_mode;
670 
671  vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_SET_MODE;
672  vcmd.target_system = new_mode.target_system;
673  vcmd.target_component = MAV_COMP_ID_ALL;
674  vcmd.source_system = msg->sysid;
675  vcmd.source_component = msg->compid;
676  vcmd.confirmation = true;
677  vcmd.from_external = true;
678 
679  _cmd_pub.publish(vcmd);
680 }
681 
682 void
684 {
685  mavlink_distance_sensor_t dist_sensor;
686  mavlink_msg_distance_sensor_decode(msg, &dist_sensor);
687 
688  distance_sensor_s ds{};
689 
690  ds.timestamp = hrt_absolute_time(); /* Use system time for now, don't trust sender to attach correct timestamp */
691  ds.min_distance = static_cast<float>(dist_sensor.min_distance) * 1e-2f; /* cm to m */
692  ds.max_distance = static_cast<float>(dist_sensor.max_distance) * 1e-2f; /* cm to m */
693  ds.current_distance = static_cast<float>(dist_sensor.current_distance) * 1e-2f; /* cm to m */
694  ds.variance = dist_sensor.covariance * 1e-4f; /* cm^2 to m^2 */
695  ds.h_fov = dist_sensor.horizontal_fov;
696  ds.v_fov = dist_sensor.vertical_fov;
697  ds.q[0] = dist_sensor.quaternion[0];
698  ds.q[1] = dist_sensor.quaternion[1];
699  ds.q[2] = dist_sensor.quaternion[2];
700  ds.q[3] = dist_sensor.quaternion[3];
701  ds.signal_quality = -1; // TODO: A dist_sensor.signal_quality field is missing from the mavlink message definition.
702  ds.type = dist_sensor.type;
703  ds.id = MAV_DISTANCE_SENSOR_LASER;
704  ds.orientation = dist_sensor.orientation;
705 
707 }
708 
709 void
711 {
712  mavlink_att_pos_mocap_t mocap;
713  mavlink_msg_att_pos_mocap_decode(msg, &mocap);
714 
715  vehicle_odometry_s mocap_odom{};
716 
717  mocap_odom.timestamp = _mavlink_timesync.sync_stamp(mocap.time_usec);
718  mocap_odom.x = mocap.x;
719  mocap_odom.y = mocap.y;
720  mocap_odom.z = mocap.z;
721  mocap_odom.q[0] = mocap.q[0];
722  mocap_odom.q[1] = mocap.q[1];
723  mocap_odom.q[2] = mocap.q[2];
724  mocap_odom.q[3] = mocap.q[3];
725 
726  const size_t URT_SIZE = sizeof(mocap_odom.pose_covariance) / sizeof(mocap_odom.pose_covariance[0]);
727  static_assert(URT_SIZE == (sizeof(mocap.covariance) / sizeof(mocap.covariance[0])),
728  "Odometry Pose Covariance matrix URT array size mismatch");
729 
730  for (size_t i = 0; i < URT_SIZE; i++) {
731  mocap_odom.pose_covariance[i] = mocap.covariance[i];
732  }
733 
734  mocap_odom.vx = NAN;
735  mocap_odom.vy = NAN;
736  mocap_odom.vz = NAN;
737  mocap_odom.rollspeed = NAN;
738  mocap_odom.pitchspeed = NAN;
739  mocap_odom.yawspeed = NAN;
740  mocap_odom.velocity_covariance[0] = NAN;
741 
742  _mocap_odometry_pub.publish(mocap_odom);
743 }
744 
745 void
747 {
748  mavlink_set_position_target_local_ned_t set_position_target_local_ned;
749  mavlink_msg_set_position_target_local_ned_decode(msg, &set_position_target_local_ned);
750 
751  const bool values_finite =
752  PX4_ISFINITE(set_position_target_local_ned.x) &&
753  PX4_ISFINITE(set_position_target_local_ned.y) &&
754  PX4_ISFINITE(set_position_target_local_ned.z) &&
755  PX4_ISFINITE(set_position_target_local_ned.vx) &&
756  PX4_ISFINITE(set_position_target_local_ned.vy) &&
757  PX4_ISFINITE(set_position_target_local_ned.vz) &&
758  PX4_ISFINITE(set_position_target_local_ned.afx) &&
759  PX4_ISFINITE(set_position_target_local_ned.afy) &&
760  PX4_ISFINITE(set_position_target_local_ned.afz) &&
761  PX4_ISFINITE(set_position_target_local_ned.yaw);
762 
763  /* Only accept messages which are intended for this system */
764  if ((mavlink_system.sysid == set_position_target_local_ned.target_system ||
765  set_position_target_local_ned.target_system == 0) &&
766  (mavlink_system.compid == set_position_target_local_ned.target_component ||
767  set_position_target_local_ned.target_component == 0) &&
768  values_finite) {
769 
770  offboard_control_mode_s offboard_control_mode{};
771 
772  /* convert mavlink type (local, NED) to uORB offboard control struct */
773  offboard_control_mode.ignore_position = (bool)(set_position_target_local_ned.type_mask & 0x7);
774  offboard_control_mode.ignore_alt_hold = (bool)(set_position_target_local_ned.type_mask & 0x4);
775  offboard_control_mode.ignore_velocity = (bool)(set_position_target_local_ned.type_mask & 0x38);
776  offboard_control_mode.ignore_acceleration_force = (bool)(set_position_target_local_ned.type_mask & 0x1C0);
777  offboard_control_mode.ignore_attitude = (bool)(set_position_target_local_ned.type_mask & 0x400);
778  offboard_control_mode.ignore_bodyrate_x = (bool)(set_position_target_local_ned.type_mask & 0x800);
779  offboard_control_mode.ignore_bodyrate_y = (bool)(set_position_target_local_ned.type_mask & 0x800);
780  offboard_control_mode.ignore_bodyrate_z = (bool)(set_position_target_local_ned.type_mask & 0x800);
781 
782  /* yaw ignore flag mapps to ignore_attitude */
783  bool is_force_sp = (bool)(set_position_target_local_ned.type_mask & (1 << 9));
784 
785  bool is_takeoff_sp = (bool)(set_position_target_local_ned.type_mask & 0x1000);
786  bool is_land_sp = (bool)(set_position_target_local_ned.type_mask & 0x2000);
787  bool is_loiter_sp = (bool)(set_position_target_local_ned.type_mask & 0x3000);
788  bool is_idle_sp = (bool)(set_position_target_local_ned.type_mask & 0x4000);
789 
790  offboard_control_mode.timestamp = hrt_absolute_time();
791  _offboard_control_mode_pub.publish(offboard_control_mode);
792 
793  /* If we are in offboard control mode and offboard control loop through is enabled
794  * also publish the setpoint topic which is read by the controller */
796 
797  vehicle_control_mode_s control_mode{};
798  _control_mode_sub.copy(&control_mode);
799 
800  if (control_mode.flag_control_offboard_enabled) {
801  if (is_force_sp && offboard_control_mode.ignore_position &&
802  offboard_control_mode.ignore_velocity) {
803 
804  PX4_WARN("force setpoint not supported");
805 
806  } else {
807  /* It's not a pure force setpoint: publish to setpoint triplet topic */
808  position_setpoint_triplet_s pos_sp_triplet{};
809 
810  pos_sp_triplet.timestamp = hrt_absolute_time();
811  pos_sp_triplet.previous.valid = false;
812  pos_sp_triplet.next.valid = false;
813  pos_sp_triplet.current.valid = true;
814 
815  /* Order of statements matters. Takeoff can override loiter.
816  * See https://github.com/mavlink/mavlink/pull/670 for a broader conversation. */
817  if (is_loiter_sp) {
818  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_LOITER;
819 
820  } else if (is_takeoff_sp) {
821  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_TAKEOFF;
822 
823  } else if (is_land_sp) {
824  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_LAND;
825 
826  } else if (is_idle_sp) {
827  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_IDLE;
828 
829  } else {
830  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_POSITION;
831  }
832 
833  /* set the local pos values */
834  if (!offboard_control_mode.ignore_position) {
835 
836  pos_sp_triplet.current.position_valid = true;
837  pos_sp_triplet.current.x = set_position_target_local_ned.x;
838  pos_sp_triplet.current.y = set_position_target_local_ned.y;
839  pos_sp_triplet.current.z = set_position_target_local_ned.z;
840 
841  } else {
842  pos_sp_triplet.current.position_valid = false;
843  }
844 
845  /* set the local vel values */
846  if (!offboard_control_mode.ignore_velocity) {
847 
848  pos_sp_triplet.current.velocity_valid = true;
849  pos_sp_triplet.current.vx = set_position_target_local_ned.vx;
850  pos_sp_triplet.current.vy = set_position_target_local_ned.vy;
851  pos_sp_triplet.current.vz = set_position_target_local_ned.vz;
852 
853  pos_sp_triplet.current.velocity_frame = set_position_target_local_ned.coordinate_frame;
854 
855  } else {
856  pos_sp_triplet.current.velocity_valid = false;
857  }
858 
859  if (!offboard_control_mode.ignore_alt_hold) {
860  pos_sp_triplet.current.alt_valid = true;
861  pos_sp_triplet.current.z = set_position_target_local_ned.z;
862 
863  } else {
864  pos_sp_triplet.current.alt_valid = false;
865  }
866 
867  /* set the local acceleration values if the setpoint type is 'local pos' and none
868  * of the accelerations fields is set to 'ignore' */
869  if (!offboard_control_mode.ignore_acceleration_force) {
870 
871  pos_sp_triplet.current.acceleration_valid = true;
872  pos_sp_triplet.current.a_x = set_position_target_local_ned.afx;
873  pos_sp_triplet.current.a_y = set_position_target_local_ned.afy;
874  pos_sp_triplet.current.a_z = set_position_target_local_ned.afz;
875  pos_sp_triplet.current.acceleration_is_force = is_force_sp;
876 
877  } else {
878  pos_sp_triplet.current.acceleration_valid = false;
879  }
880 
881  /* set the yaw sp value */
882  if (!offboard_control_mode.ignore_attitude) {
883  pos_sp_triplet.current.yaw_valid = true;
884  pos_sp_triplet.current.yaw = set_position_target_local_ned.yaw;
885 
886  } else {
887  pos_sp_triplet.current.yaw_valid = false;
888  }
889 
890  /* set the yawrate sp value */
891  if (!(offboard_control_mode.ignore_bodyrate_x ||
892  offboard_control_mode.ignore_bodyrate_y ||
893  offboard_control_mode.ignore_bodyrate_z)) {
894 
895  pos_sp_triplet.current.yawspeed_valid = true;
896  pos_sp_triplet.current.yawspeed = set_position_target_local_ned.yaw_rate;
897 
898  } else {
899  pos_sp_triplet.current.yawspeed_valid = false;
900  }
901 
902  //XXX handle global pos setpoints (different MAV frames)
903  _pos_sp_triplet_pub.publish(pos_sp_triplet);
904  }
905  }
906  }
907  }
908 }
909 
910 void
912 {
913  mavlink_set_position_target_global_int_t set_position_target_global_int;
914  mavlink_msg_set_position_target_global_int_decode(msg, &set_position_target_global_int);
915 
916  const bool values_finite =
917  PX4_ISFINITE(set_position_target_global_int.alt) &&
918  PX4_ISFINITE(set_position_target_global_int.vx) &&
919  PX4_ISFINITE(set_position_target_global_int.vy) &&
920  PX4_ISFINITE(set_position_target_global_int.vz) &&
921  PX4_ISFINITE(set_position_target_global_int.afx) &&
922  PX4_ISFINITE(set_position_target_global_int.afy) &&
923  PX4_ISFINITE(set_position_target_global_int.afz) &&
924  PX4_ISFINITE(set_position_target_global_int.yaw);
925 
926  /* Only accept messages which are intended for this system */
927  if ((mavlink_system.sysid == set_position_target_global_int.target_system ||
928  set_position_target_global_int.target_system == 0) &&
929  (mavlink_system.compid == set_position_target_global_int.target_component ||
930  set_position_target_global_int.target_component == 0) &&
931  values_finite) {
932 
933  offboard_control_mode_s offboard_control_mode{};
934 
935  /* convert mavlink type (local, NED) to uORB offboard control struct */
936  offboard_control_mode.ignore_position = (bool)(set_position_target_global_int.type_mask &
937  (POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_X_IGNORE
938  | POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_Y_IGNORE
939  | POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_Z_IGNORE));
940  offboard_control_mode.ignore_alt_hold = (bool)(set_position_target_global_int.type_mask & 0x4);
941  offboard_control_mode.ignore_velocity = (bool)(set_position_target_global_int.type_mask &
942  (POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_VX_IGNORE
943  | POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_VY_IGNORE
944  | POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_VZ_IGNORE));
945  offboard_control_mode.ignore_acceleration_force = (bool)(set_position_target_global_int.type_mask &
946  (POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_AX_IGNORE
947  | POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_AY_IGNORE
948  | POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_AZ_IGNORE));
949  /* yaw ignore flag mapps to ignore_attitude */
950  offboard_control_mode.ignore_attitude = (bool)(set_position_target_global_int.type_mask &
951  POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_YAW_IGNORE);
952  offboard_control_mode.ignore_bodyrate_x = (bool)(set_position_target_global_int.type_mask &
953  POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE);
954  offboard_control_mode.ignore_bodyrate_y = (bool)(set_position_target_global_int.type_mask &
955  POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE);
956  offboard_control_mode.ignore_bodyrate_z = (bool)(set_position_target_global_int.type_mask &
957  POSITION_TARGET_TYPEMASK::POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE);
958 
959  bool is_force_sp = (bool)(set_position_target_global_int.type_mask & (1 << 9));
960 
961  offboard_control_mode.timestamp = hrt_absolute_time();
962  _offboard_control_mode_pub.publish(offboard_control_mode);
963 
964  /* If we are in offboard control mode and offboard control loop through is enabled
965  * also publish the setpoint topic which is read by the controller */
967 
968  vehicle_control_mode_s control_mode{};
969  _control_mode_sub.copy(&control_mode);
970 
971  if (control_mode.flag_control_offboard_enabled) {
972  if (is_force_sp && offboard_control_mode.ignore_position &&
973  offboard_control_mode.ignore_velocity) {
974 
975  PX4_WARN("force setpoint not supported");
976 
977  } else {
978  /* It's not a pure force setpoint: publish to setpoint triplet topic */
979  position_setpoint_triplet_s pos_sp_triplet{};
980 
981  pos_sp_triplet.timestamp = hrt_absolute_time();
982  pos_sp_triplet.previous.valid = false;
983  pos_sp_triplet.next.valid = false;
984  pos_sp_triplet.current.valid = true;
985 
986  /* Order of statements matters. Takeoff can override loiter.
987  * See https://github.com/mavlink/mavlink/pull/670 for a broader conversation. */
988  if (set_position_target_global_int.type_mask & 0x3000) { //Loiter setpoint
989  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_LOITER;
990 
991  } else if (set_position_target_global_int.type_mask & 0x1000) { //Takeoff setpoint
992  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_TAKEOFF;
993 
994  } else if (set_position_target_global_int.type_mask & 0x2000) { //Land setpoint
995  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_LAND;
996 
997  } else if (set_position_target_global_int.type_mask & 0x4000) { //Idle setpoint
998  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_IDLE;
999 
1000  } else {
1001  pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_POSITION;
1002  }
1003 
1004  /* set the local pos values */
1005  vehicle_local_position_s local_pos{};
1006 
1007  if (!offboard_control_mode.ignore_position && _vehicle_local_position_sub.copy(&local_pos)) {
1009  globallocalconverter_init(local_pos.ref_lat, local_pos.ref_lon,
1010  local_pos.ref_alt, local_pos.ref_timestamp);
1011  pos_sp_triplet.current.position_valid = false;
1012 
1013  } else {
1014  globallocalconverter_tolocal(set_position_target_global_int.lat_int / 1e7,
1015  set_position_target_global_int.lon_int / 1e7, set_position_target_global_int.alt,
1016  &pos_sp_triplet.current.x, &pos_sp_triplet.current.y, &pos_sp_triplet.current.z);
1017  pos_sp_triplet.current.position_valid = true;
1018  }
1019 
1020  } else {
1021  pos_sp_triplet.current.position_valid = false;
1022  }
1023 
1024  /* set the local velocity values */
1025  if (!offboard_control_mode.ignore_velocity) {
1026 
1027  pos_sp_triplet.current.velocity_valid = true;
1028  pos_sp_triplet.current.vx = set_position_target_global_int.vx;
1029  pos_sp_triplet.current.vy = set_position_target_global_int.vy;
1030  pos_sp_triplet.current.vz = set_position_target_global_int.vz;
1031 
1032  pos_sp_triplet.current.velocity_frame = set_position_target_global_int.coordinate_frame;
1033 
1034  } else {
1035  pos_sp_triplet.current.velocity_valid = false;
1036  }
1037 
1038  if (!offboard_control_mode.ignore_alt_hold) {
1039  pos_sp_triplet.current.alt_valid = true;
1040 
1041  } else {
1042  pos_sp_triplet.current.alt_valid = false;
1043  }
1044 
1045  /* set the local acceleration values if the setpoint type is 'local pos' and none
1046  * of the accelerations fields is set to 'ignore' */
1047  if (!offboard_control_mode.ignore_acceleration_force) {
1048 
1049  pos_sp_triplet.current.acceleration_valid = true;
1050  pos_sp_triplet.current.a_x = set_position_target_global_int.afx;
1051  pos_sp_triplet.current.a_y = set_position_target_global_int.afy;
1052  pos_sp_triplet.current.a_z = set_position_target_global_int.afz;
1053  pos_sp_triplet.current.acceleration_is_force = is_force_sp;
1054 
1055  } else {
1056  pos_sp_triplet.current.acceleration_valid = false;
1057  }
1058 
1059  /* set the yaw setpoint */
1060  if (!offboard_control_mode.ignore_attitude) {
1061  pos_sp_triplet.current.yaw_valid = true;
1062  pos_sp_triplet.current.yaw = set_position_target_global_int.yaw;
1063 
1064  } else {
1065  pos_sp_triplet.current.yaw_valid = false;
1066  }
1067 
1068  /* set the yawrate sp value */
1069  if (!(offboard_control_mode.ignore_bodyrate_x ||
1070  offboard_control_mode.ignore_bodyrate_y ||
1071  offboard_control_mode.ignore_bodyrate_z)) {
1072 
1073  pos_sp_triplet.current.yawspeed_valid = true;
1074  pos_sp_triplet.current.yawspeed = set_position_target_global_int.yaw_rate;
1075 
1076  } else {
1077  pos_sp_triplet.current.yawspeed_valid = false;
1078  }
1079 
1080  _pos_sp_triplet_pub.publish(pos_sp_triplet);
1081  }
1082  }
1083  }
1084  }
1085 }
1086 
1087 void
1089 {
1090  mavlink_set_actuator_control_target_t set_actuator_control_target;
1091  mavlink_msg_set_actuator_control_target_decode(msg, &set_actuator_control_target);
1092 
1093  bool values_finite =
1094  PX4_ISFINITE(set_actuator_control_target.controls[0]) &&
1095  PX4_ISFINITE(set_actuator_control_target.controls[1]) &&
1096  PX4_ISFINITE(set_actuator_control_target.controls[2]) &&
1097  PX4_ISFINITE(set_actuator_control_target.controls[3]) &&
1098  PX4_ISFINITE(set_actuator_control_target.controls[4]) &&
1099  PX4_ISFINITE(set_actuator_control_target.controls[5]) &&
1100  PX4_ISFINITE(set_actuator_control_target.controls[6]) &&
1101  PX4_ISFINITE(set_actuator_control_target.controls[7]);
1102 
1103  if ((mavlink_system.sysid == set_actuator_control_target.target_system ||
1104  set_actuator_control_target.target_system == 0) &&
1105  (mavlink_system.compid == set_actuator_control_target.target_component ||
1106  set_actuator_control_target.target_component == 0) &&
1107  values_finite) {
1108 
1109 #if defined(ENABLE_LOCKSTEP_SCHEDULER)
1110  PX4_ERR("SET_ACTUATOR_CONTROL_TARGET not supported with lockstep enabled");
1111  PX4_ERR("Please disable lockstep for actuator offboard control:");
1112  PX4_ERR("https://dev.px4.io/master/en/simulation/#disable-lockstep-simulation");
1113  return;
1114 #endif
1115  /* Ignore all setpoints except when controlling the gimbal(group_mlx==2) as we are setting raw actuators here */
1116  bool ignore_setpoints = bool(set_actuator_control_target.group_mlx != 2);
1117 
1118  offboard_control_mode_s offboard_control_mode{};
1119 
1120  offboard_control_mode.ignore_thrust = ignore_setpoints;
1121  offboard_control_mode.ignore_attitude = ignore_setpoints;
1122  offboard_control_mode.ignore_bodyrate_x = ignore_setpoints;
1123  offboard_control_mode.ignore_bodyrate_y = ignore_setpoints;
1124  offboard_control_mode.ignore_bodyrate_z = ignore_setpoints;
1125  offboard_control_mode.ignore_position = ignore_setpoints;
1126  offboard_control_mode.ignore_velocity = ignore_setpoints;
1127  offboard_control_mode.ignore_acceleration_force = ignore_setpoints;
1128 
1129  offboard_control_mode.timestamp = hrt_absolute_time();
1130 
1131  _offboard_control_mode_pub.publish(offboard_control_mode);
1132 
1133  /* If we are in offboard control mode, publish the actuator controls */
1134  vehicle_control_mode_s control_mode{};
1135  _control_mode_sub.copy(&control_mode);
1136 
1137  if (control_mode.flag_control_offboard_enabled) {
1138 
1140  actuator_controls.timestamp = hrt_absolute_time();
1141 
1142  /* Set duty cycles for the servos in the actuator_controls message */
1143  for (size_t i = 0; i < 8; i++) {
1144  actuator_controls.control[i] = set_actuator_control_target.controls[i];
1145  }
1146 
1147  switch (set_actuator_control_target.group_mlx) {
1148  case 0:
1150  break;
1151 
1152  case 1:
1154  break;
1155 
1156  case 2:
1158  break;
1159 
1160  case 3:
1162  break;
1163 
1164  default:
1165  break;
1166  }
1167  }
1168  }
1169 
1170 }
1171 
1172 void
1174 {
1175  mavlink_gps_global_origin_t origin;
1176  mavlink_msg_gps_global_origin_decode(msg, &origin);
1177 
1179  /* Set reference point conversion of local coordiantes <--> global coordinates */
1180  globallocalconverter_init((double)origin.latitude * 1.0e-7, (double)origin.longitude * 1.0e-7,
1181  (float)origin.altitude * 1.0e-3f, hrt_absolute_time());
1183 
1184  }
1185 }
1186 
1187 void
1189 {
1190  mavlink_vision_position_estimate_t ev;
1191  mavlink_msg_vision_position_estimate_decode(msg, &ev);
1192 
1193  vehicle_odometry_s visual_odom{};
1194 
1195  visual_odom.timestamp = _mavlink_timesync.sync_stamp(ev.usec);
1196  visual_odom.x = ev.x;
1197  visual_odom.y = ev.y;
1198  visual_odom.z = ev.z;
1199  matrix::Quatf q(matrix::Eulerf(ev.roll, ev.pitch, ev.yaw));
1200  q.copyTo(visual_odom.q);
1201 
1202  // TODO:
1203  // - add a MAV_FRAME_*_OTHER to the Mavlink MAV_FRAME enum IOT define
1204  // a frame of reference which is not aligned with NED or ENU
1205  // - add usage on the estimator side
1206  visual_odom.local_frame = visual_odom.LOCAL_FRAME_NED;
1207 
1208  const size_t URT_SIZE = sizeof(visual_odom.pose_covariance) / sizeof(visual_odom.pose_covariance[0]);
1209  static_assert(URT_SIZE == (sizeof(ev.covariance) / sizeof(ev.covariance[0])),
1210  "Odometry Pose Covariance matrix URT array size mismatch");
1211 
1212  for (size_t i = 0; i < URT_SIZE; i++) {
1213  visual_odom.pose_covariance[i] = ev.covariance[i];
1214  }
1215 
1216  visual_odom.vx = NAN;
1217  visual_odom.vy = NAN;
1218  visual_odom.vz = NAN;
1219  visual_odom.rollspeed = NAN;
1220  visual_odom.pitchspeed = NAN;
1221  visual_odom.yawspeed = NAN;
1222  visual_odom.velocity_covariance[0] = NAN;
1223 
1224  _visual_odometry_pub.publish(visual_odom);
1225 }
1226 
1227 void
1229 {
1230  mavlink_odometry_t odom;
1231  mavlink_msg_odometry_decode(msg, &odom);
1232 
1233  vehicle_odometry_s odometry{};
1234 
1235  odometry.timestamp = _mavlink_timesync.sync_stamp(odom.time_usec);
1236 
1237  /* The position is in a local FRD frame */
1238  odometry.x = odom.x;
1239  odometry.y = odom.y;
1240  odometry.z = odom.z;
1241 
1242  /* The quaternion of the ODOMETRY msg represents a rotation from body frame to
1243  * a local frame*/
1244  matrix::Quatf q_body_to_local(odom.q);
1245  q_body_to_local.normalize();
1246  q_body_to_local.copyTo(odometry.q);
1247 
1248  // TODO:
1249  // - add a MAV_FRAME_*_OTHER to the Mavlink MAV_FRAME enum IOT define
1250  // a frame of reference which is not aligned with NED or ENU
1251  // - add usage on the estimator side
1252  odometry.local_frame = odometry.LOCAL_FRAME_NED;
1253 
1254  // pose_covariance
1255  static constexpr size_t POS_URT_SIZE = sizeof(odometry.pose_covariance) / sizeof(odometry.pose_covariance[0]);
1256  static_assert(POS_URT_SIZE == (sizeof(odom.pose_covariance) / sizeof(odom.pose_covariance[0])),
1257  "Odometry Pose Covariance matrix URT array size mismatch");
1258 
1259  // velocity_covariance
1260  static constexpr size_t VEL_URT_SIZE = sizeof(odometry.velocity_covariance) / sizeof(odometry.velocity_covariance[0]);
1261  static_assert(VEL_URT_SIZE == (sizeof(odom.velocity_covariance) / sizeof(odom.velocity_covariance[0])),
1262  "Odometry Velocity Covariance matrix URT array size mismatch");
1263 
1264  // create a method to simplify covariance copy
1265  for (size_t i = 0; i < POS_URT_SIZE; i++) {
1266  odometry.pose_covariance[i] = odom.pose_covariance[i];
1267  }
1268 
1269  /*
1270  * PX4 expects the body's linear velocity in the local frame,
1271  * the linear velocity is rotated from the odom child_frame to the
1272  * local NED frame. The angular velocity needs to be expressed in the
1273  * body (fcu_frd) frame.
1274  */
1275  if (odom.child_frame_id == MAV_FRAME_BODY_FRD) {
1276  /* Linear velocity has to be rotated to the local NED frame
1277  * Angular velocities are already in the right body frame */
1278  const matrix::Dcmf R_body_to_local = matrix::Dcmf(q_body_to_local);
1279 
1280  /* the linear velocities needs to be transformed to the local NED frame */
1281  matrix::Vector3<float> linvel_local(R_body_to_local * matrix::Vector3<float>(odom.vx, odom.vy, odom.vz));
1282 
1283  odometry.vx = linvel_local(0);
1284  odometry.vy = linvel_local(1);
1285  odometry.vz = linvel_local(2);
1286 
1287  odometry.rollspeed = odom.rollspeed;
1288  odometry.pitchspeed = odom.pitchspeed;
1289  odometry.yawspeed = odom.yawspeed;
1290 
1291  //TODO: Apply rotation matrix to transform from body-fixed NED to earth-fixed NED frame
1292  for (size_t i = 0; i < VEL_URT_SIZE; i++) {
1293  odometry.velocity_covariance[i] = odom.velocity_covariance[i];
1294  }
1295 
1296  } else {
1297  PX4_ERR("Body frame %u not supported. Unable to publish velocity", odom.child_frame_id);
1298  }
1299 
1300  if (odom.frame_id == MAV_FRAME_LOCAL_FRD) {
1301  _visual_odometry_pub.publish(odometry);
1302 
1303  } else if (odom.frame_id == MAV_FRAME_MOCAP_NED) {
1304  _mocap_odometry_pub.publish(odometry);
1305 
1306  } else {
1307  PX4_ERR("Local frame %u not supported. Unable to publish pose and velocity", odom.frame_id);
1308  }
1309 }
1310 
1311 void MavlinkReceiver::fill_thrust(float *thrust_body_array, uint8_t vehicle_type, float thrust)
1312 {
1313  // Fill correct field by checking frametype
1314  // TODO: add as needed
1315  switch (_mavlink->get_system_type()) {
1316  case MAV_TYPE_GENERIC:
1317  break;
1318 
1319  case MAV_TYPE_FIXED_WING:
1320  case MAV_TYPE_GROUND_ROVER:
1321  thrust_body_array[0] = thrust;
1322  break;
1323 
1324  case MAV_TYPE_QUADROTOR:
1325  case MAV_TYPE_HEXAROTOR:
1326  case MAV_TYPE_OCTOROTOR:
1327  case MAV_TYPE_TRICOPTER:
1328  case MAV_TYPE_HELICOPTER:
1329  thrust_body_array[2] = -thrust;
1330  break;
1331 
1332  case MAV_TYPE_VTOL_DUOROTOR:
1333  case MAV_TYPE_VTOL_QUADROTOR:
1334  case MAV_TYPE_VTOL_TILTROTOR:
1335  case MAV_TYPE_VTOL_RESERVED2:
1336  case MAV_TYPE_VTOL_RESERVED3:
1337  case MAV_TYPE_VTOL_RESERVED4:
1338  case MAV_TYPE_VTOL_RESERVED5:
1339  switch (vehicle_type) {
1341  thrust_body_array[0] = thrust;
1342 
1343  break;
1344 
1345  case vehicle_status_s::VEHICLE_TYPE_ROTARY_WING:
1346  thrust_body_array[2] = -thrust;
1347 
1348  break;
1349 
1350  default:
1351  // This should never happen
1352  break;
1353  }
1354 
1355  break;
1356  }
1357 }
1358 
1359 void
1361 {
1362  mavlink_set_attitude_target_t set_attitude_target;
1363  mavlink_msg_set_attitude_target_decode(msg, &set_attitude_target);
1364 
1365  bool values_finite =
1366  PX4_ISFINITE(set_attitude_target.q[0]) &&
1367  PX4_ISFINITE(set_attitude_target.q[1]) &&
1368  PX4_ISFINITE(set_attitude_target.q[2]) &&
1369  PX4_ISFINITE(set_attitude_target.q[3]) &&
1370  PX4_ISFINITE(set_attitude_target.thrust) &&
1371  PX4_ISFINITE(set_attitude_target.body_roll_rate) &&
1372  PX4_ISFINITE(set_attitude_target.body_pitch_rate) &&
1373  PX4_ISFINITE(set_attitude_target.body_yaw_rate);
1374 
1375  /* Only accept messages which are intended for this system */
1376  if ((mavlink_system.sysid == set_attitude_target.target_system ||
1377  set_attitude_target.target_system == 0) &&
1378  (mavlink_system.compid == set_attitude_target.target_component ||
1379  set_attitude_target.target_component == 0) &&
1380  values_finite) {
1381 
1382  offboard_control_mode_s offboard_control_mode{};
1383 
1384  /* set correct ignore flags for thrust field: copy from mavlink message */
1385  offboard_control_mode.ignore_thrust = (bool)(set_attitude_target.type_mask & (1 << 6));
1386 
1387  /*
1388  * The tricky part in parsing this message is that the offboard sender *can* set attitude and thrust
1389  * using different messages. Eg.: First send set_attitude_target containing the attitude and ignore
1390  * bits set for everything else and then send set_attitude_target containing the thrust and ignore bits
1391  * set for everything else.
1392  */
1393 
1394  /*
1395  * if attitude or body rate have been used (not ignored) previously and this message only sends
1396  * throttle and has the ignore bits set for attitude and rates don't change the flags for attitude and
1397  * body rates to keep the controllers running
1398  */
1399  bool ignore_bodyrate_msg_x = (bool)(set_attitude_target.type_mask & 0x1);
1400  bool ignore_bodyrate_msg_y = (bool)(set_attitude_target.type_mask & 0x2);
1401  bool ignore_bodyrate_msg_z = (bool)(set_attitude_target.type_mask & 0x4);
1402  bool ignore_attitude_msg = (bool)(set_attitude_target.type_mask & (1 << 7));
1403 
1404 
1405  if ((ignore_bodyrate_msg_x || ignore_bodyrate_msg_y ||
1406  ignore_bodyrate_msg_z) &&
1407  ignore_attitude_msg && !offboard_control_mode.ignore_thrust) {
1408 
1409  /* Message want's us to ignore everything except thrust: only ignore if previously ignored */
1410  offboard_control_mode.ignore_bodyrate_x = ignore_bodyrate_msg_x && offboard_control_mode.ignore_bodyrate_x;
1411  offboard_control_mode.ignore_bodyrate_y = ignore_bodyrate_msg_y && offboard_control_mode.ignore_bodyrate_y;
1412  offboard_control_mode.ignore_bodyrate_z = ignore_bodyrate_msg_z && offboard_control_mode.ignore_bodyrate_z;
1413  offboard_control_mode.ignore_attitude = ignore_attitude_msg && offboard_control_mode.ignore_attitude;
1414 
1415  } else {
1416  offboard_control_mode.ignore_bodyrate_x = ignore_bodyrate_msg_x;
1417  offboard_control_mode.ignore_bodyrate_y = ignore_bodyrate_msg_y;
1418  offboard_control_mode.ignore_bodyrate_z = ignore_bodyrate_msg_z;
1419  offboard_control_mode.ignore_attitude = ignore_attitude_msg;
1420  }
1421 
1422  offboard_control_mode.ignore_position = true;
1423  offboard_control_mode.ignore_velocity = true;
1424  offboard_control_mode.ignore_acceleration_force = true;
1425 
1426  offboard_control_mode.timestamp = hrt_absolute_time();
1427 
1428  _offboard_control_mode_pub.publish(offboard_control_mode);
1429 
1430  /* If we are in offboard control mode and offboard control loop through is enabled
1431  * also publish the setpoint topic which is read by the controller */
1433 
1434  vehicle_control_mode_s control_mode{};
1435  _control_mode_sub.copy(&control_mode);
1436 
1437  if (control_mode.flag_control_offboard_enabled) {
1438  vehicle_status_s vehicle_status{};
1439  _vehicle_status_sub.copy(&vehicle_status);
1440 
1441  /* Publish attitude setpoint if attitude and thrust ignore bits are not set */
1442  if (!(offboard_control_mode.ignore_attitude)) {
1443  vehicle_attitude_setpoint_s att_sp = {};
1444  att_sp.timestamp = hrt_absolute_time();
1445 
1446  if (!ignore_attitude_msg) { // only copy att sp if message contained new data
1447  matrix::Quatf q(set_attitude_target.q);
1448  q.copyTo(att_sp.q_d);
1449  att_sp.q_d_valid = true;
1450 
1451  matrix::Eulerf euler{q};
1452  att_sp.roll_body = euler.phi();
1453  att_sp.pitch_body = euler.theta();
1454  att_sp.yaw_body = euler.psi();
1455  att_sp.yaw_sp_move_rate = 0.0f;
1456  }
1457 
1458  if (!offboard_control_mode.ignore_thrust) { // dont't overwrite thrust if it's invalid
1459  fill_thrust(att_sp.thrust_body, vehicle_status.vehicle_type, set_attitude_target.thrust);
1460  }
1461 
1462  // Publish attitude setpoint
1463  if (vehicle_status.is_vtol && (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING)) {
1465 
1466  } else if (vehicle_status.is_vtol && (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING)) {
1468 
1469  } else {
1470  _att_sp_pub.publish(att_sp);
1471  }
1472  }
1473 
1474  /* Publish attitude rate setpoint if bodyrate and thrust ignore bits are not set */
1475  if (!offboard_control_mode.ignore_bodyrate_x ||
1476  !offboard_control_mode.ignore_bodyrate_y ||
1477  !offboard_control_mode.ignore_bodyrate_z) {
1478 
1479  vehicle_rates_setpoint_s rates_sp{};
1480 
1481  rates_sp.timestamp = hrt_absolute_time();
1482 
1483  // only copy att rates sp if message contained new data
1484  if (!ignore_bodyrate_msg_x) {
1485  rates_sp.roll = set_attitude_target.body_roll_rate;
1486  }
1487 
1488  if (!ignore_bodyrate_msg_y) {
1489  rates_sp.pitch = set_attitude_target.body_pitch_rate;
1490  }
1491 
1492  if (!ignore_bodyrate_msg_z) {
1493  rates_sp.yaw = set_attitude_target.body_yaw_rate;
1494  }
1495 
1496  if (!offboard_control_mode.ignore_thrust) { // dont't overwrite thrust if it's invalid
1497  fill_thrust(rates_sp.thrust_body, vehicle_status.vehicle_type, set_attitude_target.thrust);
1498  }
1499 
1500  _rates_sp_pub.publish(rates_sp);
1501  }
1502  }
1503  }
1504  }
1505 }
1506 
1507 void
1509 {
1510  /* telemetry status supported only on first ORB_MULTI_MAX_INSTANCES mavlink channels */
1511  if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) {
1512  mavlink_radio_status_t rstatus;
1513  mavlink_msg_radio_status_decode(msg, &rstatus);
1514 
1516 
1518  status.rssi = rstatus.rssi;
1519  status.remote_rssi = rstatus.remrssi;
1520  status.txbuf = rstatus.txbuf;
1521  status.noise = rstatus.noise;
1522  status.remote_noise = rstatus.remnoise;
1523  status.rxerrors = rstatus.rxerrors;
1524  status.fix = rstatus.fixed;
1525 
1527 
1529  }
1530 }
1531 
1532 void
1534 {
1535  mavlink_ping_t ping;
1536  mavlink_msg_ping_decode(msg, &ping);
1537 
1538  if ((ping.target_system == 0) &&
1539  (ping.target_component == 0)) { // This is a ping request. Return it to the system which requested the ping.
1540 
1541  ping.target_system = msg->sysid;
1542  ping.target_component = msg->compid;
1543  mavlink_msg_ping_send_struct(_mavlink->get_channel(), &ping);
1544 
1545  } else if ((ping.target_system == mavlink_system.sysid) &&
1546  (ping.target_component ==
1547  mavlink_system.compid)) { // This is a returned ping message from this system. Calculate latency from it.
1548 
1549  const hrt_abstime now = hrt_absolute_time();
1550 
1551  // Calculate round trip time
1552  float rtt_ms = (now - ping.time_usec) / 1000.0f;
1553 
1554  // Update ping statistics
1556 
1557  pstats.last_ping_time = now;
1558 
1559  if (pstats.last_ping_seq == 0 && ping.seq > 0) {
1560  // This is the first reply we are receiving from an offboard system.
1561  // We may have been broadcasting pings for some time before it came online,
1562  // and these do not count as dropped packets.
1563 
1564  // Reset last_ping_seq counter for correct packet drop detection
1565  pstats.last_ping_seq = ping.seq - 1;
1566  }
1567 
1568  // We can only count dropped packets after the first message
1569  if (ping.seq > pstats.last_ping_seq) {
1570  pstats.dropped_packets += ping.seq - pstats.last_ping_seq - 1;
1571  }
1572 
1573  pstats.last_ping_seq = ping.seq;
1574  pstats.last_rtt = rtt_ms;
1575  pstats.mean_rtt = (rtt_ms + pstats.mean_rtt) / 2.0f;
1576  pstats.max_rtt = fmaxf(rtt_ms, pstats.max_rtt);
1577  pstats.min_rtt = pstats.min_rtt > 0.0f ? fminf(rtt_ms, pstats.min_rtt) : rtt_ms;
1578 
1579  /* Ping status is supported only on first ORB_MULTI_MAX_INSTANCES mavlink channels */
1580  if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) {
1581 
1582  ping_s uorb_ping_msg{};
1583 
1584  uorb_ping_msg.timestamp = now;
1585  uorb_ping_msg.ping_time = ping.time_usec;
1586  uorb_ping_msg.ping_sequence = ping.seq;
1587  uorb_ping_msg.dropped_packets = pstats.dropped_packets;
1588  uorb_ping_msg.rtt_ms = rtt_ms;
1589  uorb_ping_msg.system_id = msg->sysid;
1590  uorb_ping_msg.component_id = msg->compid;
1591 
1592  _ping_pub.publish(uorb_ping_msg);
1593  }
1594  }
1595 }
1596 
1597 void
1599 {
1600  if ((msg->sysid != mavlink_system.sysid) || (msg->compid == mavlink_system.compid)) {
1601  // ignore battery status coming from other systems or from the autopilot itself
1602  return;
1603  }
1604 
1605  // external battery measurements
1606  mavlink_battery_status_t battery_mavlink;
1607  mavlink_msg_battery_status_decode(msg, &battery_mavlink);
1608 
1610  battery_status.timestamp = hrt_absolute_time();
1611 
1612  float voltage_sum = 0.0f;
1613  uint8_t cell_count = 0;
1614 
1615  while (battery_mavlink.voltages[cell_count] < UINT16_MAX && cell_count < 10) {
1616  voltage_sum += (float)(battery_mavlink.voltages[cell_count]) / 1000.0f;
1617  cell_count++;
1618  }
1619 
1620  battery_status.voltage_v = voltage_sum;
1621  battery_status.voltage_filtered_v = voltage_sum;
1622  battery_status.current_a = battery_status.current_filtered_a = (float)(battery_mavlink.current_battery) / 100.0f;
1623  battery_status.current_filtered_a = battery_status.current_a;
1624  battery_status.remaining = (float)battery_mavlink.battery_remaining / 100.0f;
1625  battery_status.discharged_mah = (float)battery_mavlink.current_consumed;
1626  battery_status.cell_count = cell_count;
1627  battery_status.connected = true;
1628 
1629  // Set the battery warning based on remaining charge.
1630  // Note: Smallest values must come first in evaluation.
1631  if (battery_status.remaining < _param_bat_emergen_thr.get()) {
1632  battery_status.warning = battery_status_s::BATTERY_WARNING_EMERGENCY;
1633 
1634  } else if (battery_status.remaining < _param_bat_crit_thr.get()) {
1635  battery_status.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
1636 
1637  } else if (battery_status.remaining < _param_bat_low_thr.get()) {
1638  battery_status.warning = battery_status_s::BATTERY_WARNING_LOW;
1639  }
1640 
1642 }
1643 
1644 void
1646 {
1647  mavlink_serial_control_t serial_control_mavlink;
1648  mavlink_msg_serial_control_decode(msg, &serial_control_mavlink);
1649 
1650  // we only support shell commands
1651  if (serial_control_mavlink.device != SERIAL_CONTROL_DEV_SHELL
1652  || (serial_control_mavlink.flags & SERIAL_CONTROL_FLAG_REPLY)) {
1653  return;
1654  }
1655 
1656  MavlinkShell *shell = _mavlink->get_shell();
1657 
1658  if (shell) {
1659  // we ignore the timeout, EXCLUSIVE & BLOCKING flags of the SERIAL_CONTROL message
1660  if (serial_control_mavlink.count > 0) {
1661  shell->write(serial_control_mavlink.data, serial_control_mavlink.count);
1662  }
1663 
1664  // if no response requested, assume the shell is no longer used
1665  if ((serial_control_mavlink.flags & SERIAL_CONTROL_FLAG_RESPOND) == 0) {
1666  _mavlink->close_shell();
1667  }
1668  }
1669 }
1670 
1671 void
1673 {
1674  mavlink_logging_ack_t logging_ack;
1675  mavlink_msg_logging_ack_decode(msg, &logging_ack);
1676 
1677  MavlinkULog *ulog_streaming = _mavlink->get_ulog_streaming();
1678 
1679  if (ulog_streaming) {
1680  ulog_streaming->handle_ack(logging_ack);
1681  }
1682 }
1683 
1684 void
1686 {
1687  mavlink_play_tune_t play_tune;
1688  mavlink_msg_play_tune_decode(msg, &play_tune);
1689 
1690  char *tune = play_tune.tune;
1691 
1692  if ((mavlink_system.sysid == play_tune.target_system ||
1693  play_tune.target_system == 0) &&
1694  (mavlink_system.compid == play_tune.target_component ||
1695  play_tune.target_component == 0)) {
1696 
1697  if (*tune == 'M') {
1698  int fd = px4_open(TONE_ALARM0_DEVICE_PATH, PX4_F_WRONLY);
1699 
1700  if (fd >= 0) {
1701  px4_write(fd, tune, strlen(tune) + 1);
1702  px4_close(fd);
1703  }
1704  }
1705  }
1706 }
1707 
1708 void
1710 {
1711  mavlink_obstacle_distance_t mavlink_obstacle_distance;
1712  mavlink_msg_obstacle_distance_decode(msg, &mavlink_obstacle_distance);
1713 
1714  obstacle_distance_s obstacle_distance{};
1715 
1716  obstacle_distance.timestamp = hrt_absolute_time();
1717  obstacle_distance.sensor_type = mavlink_obstacle_distance.sensor_type;
1718  memcpy(obstacle_distance.distances, mavlink_obstacle_distance.distances, sizeof(obstacle_distance.distances));
1719 
1720  if (mavlink_obstacle_distance.increment_f > 0.f) {
1721  obstacle_distance.increment = mavlink_obstacle_distance.increment_f;
1722 
1723  } else {
1724  obstacle_distance.increment = (float)mavlink_obstacle_distance.increment;
1725  }
1726 
1727  obstacle_distance.min_distance = mavlink_obstacle_distance.min_distance;
1728  obstacle_distance.max_distance = mavlink_obstacle_distance.max_distance;
1729  obstacle_distance.angle_offset = mavlink_obstacle_distance.angle_offset;
1730  obstacle_distance.frame = mavlink_obstacle_distance.frame;
1731 
1732  _obstacle_distance_pub.publish(obstacle_distance);
1733 }
1734 
1735 void
1737 {
1738  mavlink_trajectory_representation_waypoints_t trajectory;
1739  mavlink_msg_trajectory_representation_waypoints_decode(msg, &trajectory);
1740 
1741  vehicle_trajectory_waypoint_s trajectory_waypoint{};
1742 
1743  trajectory_waypoint.timestamp = hrt_absolute_time();
1744  const int number_valid_points = trajectory.valid_points;
1745 
1746  for (int i = 0; i < vehicle_trajectory_waypoint_s::NUMBER_POINTS; ++i) {
1747  trajectory_waypoint.waypoints[i].position[0] = trajectory.pos_x[i];
1748  trajectory_waypoint.waypoints[i].position[1] = trajectory.pos_y[i];
1749  trajectory_waypoint.waypoints[i].position[2] = trajectory.pos_z[i];
1750 
1751  trajectory_waypoint.waypoints[i].velocity[0] = trajectory.vel_x[i];
1752  trajectory_waypoint.waypoints[i].velocity[1] = trajectory.vel_y[i];
1753  trajectory_waypoint.waypoints[i].velocity[2] = trajectory.vel_z[i];
1754 
1755  trajectory_waypoint.waypoints[i].acceleration[0] = trajectory.acc_x[i];
1756  trajectory_waypoint.waypoints[i].acceleration[1] = trajectory.acc_y[i];
1757  trajectory_waypoint.waypoints[i].acceleration[2] = trajectory.acc_z[i];
1758 
1759  trajectory_waypoint.waypoints[i].yaw = trajectory.pos_yaw[i];
1760  trajectory_waypoint.waypoints[i].yaw_speed = trajectory.vel_yaw[i];
1761 
1762  trajectory_waypoint.waypoints[i].type = UINT8_MAX;
1763  }
1764 
1765  for (int i = 0; i < number_valid_points; ++i) {
1766  trajectory_waypoint.waypoints[i].point_valid = true;
1767  }
1768 
1769  for (int i = number_valid_points; i < vehicle_trajectory_waypoint_s::NUMBER_POINTS; ++i) {
1770  trajectory_waypoint.waypoints[i].point_valid = false;
1771  }
1772 
1773  _trajectory_waypoint_pub.publish(trajectory_waypoint);
1774 }
1775 
1777 MavlinkReceiver::decode_switch_pos(uint16_t buttons, unsigned sw)
1778 {
1779  // This 2-bit method should be used in the future: (buttons >> (sw * 2)) & 3;
1780  return (buttons & (1 << sw)) ? manual_control_setpoint_s::SWITCH_POS_ON : manual_control_setpoint_s::SWITCH_POS_OFF;
1781 }
1782 
1783 int
1784 MavlinkReceiver::decode_switch_pos_n(uint16_t buttons, unsigned sw)
1785 {
1786  bool on = (buttons & (1 << sw));
1787 
1788  if (sw < MOM_SWITCH_COUNT) {
1789 
1790  bool last_on = (_mom_switch_state & (1 << sw));
1791 
1792  /* first switch is 2-pos, rest is 2 pos */
1793  unsigned state_count = (sw == 0) ? 3 : 2;
1794 
1795  /* only transition on low state */
1796  if (!on && (on != last_on)) {
1797 
1798  _mom_switch_pos[sw]++;
1799 
1800  if (_mom_switch_pos[sw] == state_count) {
1801  _mom_switch_pos[sw] = 0;
1802  }
1803  }
1804 
1805  /* state_count - 1 is the number of intervals and 1000 is the range,
1806  * with 2 states 0 becomes 0, 1 becomes 1000. With
1807  * 3 states 0 becomes 0, 1 becomes 500, 2 becomes 1000,
1808  * and so on for more states.
1809  */
1810  return (_mom_switch_pos[sw] * 1000) / (state_count - 1) + 1000;
1811 
1812  } else {
1813  /* return the current state */
1814  return on * 1000 + 1000;
1815  }
1816 }
1817 
1818 void
1820 {
1821  mavlink_rc_channels_override_t man;
1822  mavlink_msg_rc_channels_override_decode(msg, &man);
1823 
1824  // Check target
1825  if (man.target_system != 0 && man.target_system != _mavlink->get_system_id()) {
1826  return;
1827  }
1828 
1829  // fill uORB message
1830  input_rc_s rc{};
1831 
1832  // metadata
1834  rc.timestamp_last_signal = rc.timestamp;
1835  rc.rssi = RC_INPUT_RSSI_MAX;
1836  rc.rc_failsafe = false;
1837  rc.rc_lost = false;
1838  rc.rc_lost_frame_count = 0;
1839  rc.rc_total_frame_count = 1;
1840  rc.rc_ppm_frame_length = 0;
1841  rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK;
1842 
1843  // channels
1844  rc.values[0] = man.chan1_raw;
1845  rc.values[1] = man.chan2_raw;
1846  rc.values[2] = man.chan3_raw;
1847  rc.values[3] = man.chan4_raw;
1848  rc.values[4] = man.chan5_raw;
1849  rc.values[5] = man.chan6_raw;
1850  rc.values[6] = man.chan7_raw;
1851  rc.values[7] = man.chan8_raw;
1852  rc.values[8] = man.chan9_raw;
1853  rc.values[9] = man.chan10_raw;
1854  rc.values[10] = man.chan11_raw;
1855  rc.values[11] = man.chan12_raw;
1856  rc.values[12] = man.chan13_raw;
1857  rc.values[13] = man.chan14_raw;
1858  rc.values[14] = man.chan15_raw;
1859  rc.values[15] = man.chan16_raw;
1860  rc.values[16] = man.chan17_raw;
1861  rc.values[17] = man.chan18_raw;
1862 
1863  // check how many channels are valid
1864  for (int i = 17; i >= 0; i--) {
1865  const bool ignore_max = rc.values[i] == UINT16_MAX; // ignore any channel with value UINT16_MAX
1866  const bool ignore_zero = (i > 7) && (rc.values[i] == 0); // ignore channel 8-18 if value is 0
1867 
1868  if (ignore_max || ignore_zero) {
1869  // set all ignored values to zero
1870  rc.values[i] = 0;
1871 
1872  } else {
1873  // first channel to not ignore -> set count considering zero-based index
1874  rc.channel_count = i + 1;
1875  break;
1876  }
1877  }
1878 
1879  // publish uORB message
1880  _rc_pub.publish(rc);
1881 }
1882 
1883 void
1885 {
1886  mavlink_manual_control_t man;
1887  mavlink_msg_manual_control_decode(msg, &man);
1888 
1889  // Check target
1890  if (man.target != 0 && man.target != _mavlink->get_system_id()) {
1891  return;
1892  }
1893 
1895 
1896  input_rc_s rc{};
1898  rc.timestamp_last_signal = rc.timestamp;
1899 
1900  rc.channel_count = 8;
1901  rc.rc_failsafe = false;
1902  rc.rc_lost = false;
1903  rc.rc_lost_frame_count = 0;
1904  rc.rc_total_frame_count = 1;
1905  rc.rc_ppm_frame_length = 0;
1906  rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK;
1907  rc.rssi = RC_INPUT_RSSI_MAX;
1908 
1909  rc.values[0] = man.x / 2 + 1500; // roll
1910  rc.values[1] = man.y / 2 + 1500; // pitch
1911  rc.values[2] = man.r / 2 + 1500; // yaw
1912  rc.values[3] = math::constrain(man.z / 0.9f + 800.0f, 1000.0f, 2000.0f); // throttle
1913 
1914  /* decode all switches which fit into the channel mask */
1915  unsigned max_switch = (sizeof(man.buttons) * 8);
1916  unsigned max_channels = (sizeof(rc.values) / sizeof(rc.values[0]));
1917 
1918  if (max_switch > (max_channels - 4)) {
1919  max_switch = (max_channels - 4);
1920  }
1921 
1922  /* fill all channels */
1923  for (unsigned i = 0; i < max_switch; i++) {
1924  rc.values[i + 4] = decode_switch_pos_n(man.buttons, i);
1925  }
1926 
1927  _mom_switch_state = man.buttons;
1928 
1929  _rc_pub.publish(rc);
1930 
1931  } else {
1932  manual_control_setpoint_s manual{};
1933 
1934  manual.timestamp = hrt_absolute_time();
1935  manual.x = man.x / 1000.0f;
1936  manual.y = man.y / 1000.0f;
1937  manual.r = man.r / 1000.0f;
1938  manual.z = man.z / 1000.0f;
1939  manual.data_source = manual_control_setpoint_s::SOURCE_MAVLINK_0 + _mavlink->get_instance_id();
1940 
1941  _manual_pub.publish(manual);
1942  }
1943 }
1944 
1945 void
1947 {
1948  /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */
1949  if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) {
1950  mavlink_heartbeat_t hb;
1951  mavlink_msg_heartbeat_decode(msg, &hb);
1952 
1953  /* Accept only heartbeats from GCS or ONBOARD Controller, skip heartbeats from other vehicles */
1954  if ((msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) || (msg->sysid == mavlink_system.sysid
1955  && hb.type == MAV_TYPE_ONBOARD_CONTROLLER)) {
1956 
1958 
1959  /* set heartbeat time and topic time and publish -
1960  * the telem status also gets updated on telemetry events
1961  */
1962  tstatus.heartbeat_time = hrt_absolute_time();
1963  tstatus.remote_system_id = msg->sysid;
1964  tstatus.remote_component_id = msg->compid;
1965  tstatus.remote_type = hb.type;
1966  tstatus.remote_system_status = hb.system_status;
1967  }
1968 
1969  }
1970 }
1971 
1972 int
1973 MavlinkReceiver::set_message_interval(int msgId, float interval, int data_rate)
1974 {
1975  if (msgId == MAVLINK_MSG_ID_HEARTBEAT) {
1976  return PX4_ERROR;
1977  }
1978 
1979  if (data_rate > 0) {
1980  _mavlink->set_data_rate(data_rate);
1981  }
1982 
1983  // configure_stream wants a rate (msgs/second), so convert here.
1984  float rate = 0.f;
1985 
1986  if (interval < -0.00001f) {
1987  rate = 0.f; // stop the stream
1988 
1989  } else if (interval > 0.00001f) {
1990  rate = 1000000.0f / interval;
1991 
1992  } else {
1993  rate = -2.f; // set default rate
1994  }
1995 
1996  bool found_id = false;
1997 
1998 
1999  // The interval between two messages is in microseconds.
2000  // Set to -1 to disable and 0 to request default rate
2001  if (msgId != 0) {
2002  const char *stream_name = get_stream_name(msgId);
2003 
2004  if (stream_name != nullptr) {
2005  _mavlink->configure_stream_threadsafe(stream_name, rate);
2006  found_id = true;
2007  }
2008  }
2009 
2010  return (found_id ? PX4_OK : PX4_ERROR);
2011 }
2012 
2013 void
2015 {
2016  unsigned interval = 0;
2017 
2018  for (const auto &stream : _mavlink->get_streams()) {
2019  if (stream->get_id() == msgId) {
2020  interval = stream->get_interval();
2021  break;
2022  }
2023  }
2024 
2025  // send back this value...
2026  mavlink_msg_message_interval_send(_mavlink->get_channel(), msgId, interval);
2027 }
2028 
2029 void
2031 {
2032  mavlink_hil_sensor_t imu;
2033  mavlink_msg_hil_sensor_decode(msg, &imu);
2034 
2035  const uint64_t timestamp = hrt_absolute_time();
2036 
2037  /* airspeed */
2038  {
2039  airspeed_s airspeed{};
2040 
2041  float ias = calc_IAS(imu.diff_pressure * 1e2f);
2042  float scale = 1.0f; //assume no instrument or pitot placement errors
2043  float eas = calc_EAS_from_IAS(ias, scale);
2044  float tas = calc_TAS_from_EAS(eas, imu.abs_pressure * 100, imu.temperature);
2045 
2046  airspeed.timestamp = timestamp;
2047  airspeed.indicated_airspeed_m_s = ias;
2048  airspeed.true_airspeed_m_s = tas;
2049 
2050  _airspeed_pub.publish(airspeed);
2051  }
2052 
2053  /* gyro */
2054  {
2055  sensor_gyro_s gyro{};
2056 
2057  gyro.timestamp = timestamp;
2058  gyro.x_raw = imu.xgyro * 1000.0f;
2059  gyro.y_raw = imu.ygyro * 1000.0f;
2060  gyro.z_raw = imu.zgyro * 1000.0f;
2061  gyro.x = imu.xgyro;
2062  gyro.y = imu.ygyro;
2063  gyro.z = imu.zgyro;
2064  gyro.temperature = imu.temperature;
2065 
2066  _gyro_pub.publish(gyro);
2067  }
2068 
2069  /* accelerometer */
2070  {
2071  sensor_accel_s accel{};
2072 
2073  accel.timestamp = timestamp;
2074  accel.x_raw = imu.xacc / (CONSTANTS_ONE_G / 1000.0f);
2075  accel.y_raw = imu.yacc / (CONSTANTS_ONE_G / 1000.0f);
2076  accel.z_raw = imu.zacc / (CONSTANTS_ONE_G / 1000.0f);
2077  accel.x = imu.xacc;
2078  accel.y = imu.yacc;
2079  accel.z = imu.zacc;
2080  accel.temperature = imu.temperature;
2081 
2082  _accel_pub.publish(accel);
2083  }
2084 
2085  /* magnetometer */
2086  {
2087  sensor_mag_s mag{};
2088 
2089  mag.timestamp = timestamp;
2090  mag.x_raw = imu.xmag * 1000.0f;
2091  mag.y_raw = imu.ymag * 1000.0f;
2092  mag.z_raw = imu.zmag * 1000.0f;
2093  mag.x = imu.xmag;
2094  mag.y = imu.ymag;
2095  mag.z = imu.zmag;
2096 
2097  _mag_pub.publish(mag);
2098  }
2099 
2100  /* baro */
2101  {
2102  sensor_baro_s baro{};
2103 
2104  baro.timestamp = timestamp;
2105  baro.pressure = imu.abs_pressure;
2106  baro.temperature = imu.temperature;
2107 
2108  /* fake device ID */
2109  baro.device_id = 1234567;
2110 
2111  _baro_pub.publish(baro);
2112  }
2113 
2114  /* battery status */
2115  {
2116  battery_status_s hil_battery_status{};
2117 
2118  hil_battery_status.timestamp = timestamp;
2119  hil_battery_status.voltage_v = 11.5f;
2120  hil_battery_status.voltage_filtered_v = 11.5f;
2121  hil_battery_status.current_a = 10.0f;
2122  hil_battery_status.discharged_mah = -1.0f;
2123 
2124  _battery_pub.publish(hil_battery_status);
2125  }
2126 }
2127 
2128 void
2130 {
2131  mavlink_hil_gps_t gps;
2132  mavlink_msg_hil_gps_decode(msg, &gps);
2133 
2134  const uint64_t timestamp = hrt_absolute_time();
2135 
2136  struct vehicle_gps_position_s hil_gps = {};
2137 
2138  hil_gps.timestamp_time_relative = 0;
2139  hil_gps.time_utc_usec = gps.time_usec;
2140 
2141  hil_gps.timestamp = timestamp;
2142  hil_gps.lat = gps.lat;
2143  hil_gps.lon = gps.lon;
2144  hil_gps.alt = gps.alt;
2145  hil_gps.eph = (float)gps.eph * 1e-2f; // from cm to m
2146  hil_gps.epv = (float)gps.epv * 1e-2f; // from cm to m
2147 
2148  hil_gps.s_variance_m_s = 0.1f;
2149 
2150  hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
2151  hil_gps.vel_n_m_s = gps.vn * 1e-2f; // from cm to m
2152  hil_gps.vel_e_m_s = gps.ve * 1e-2f; // from cm to m
2153  hil_gps.vel_d_m_s = gps.vd * 1e-2f; // from cm to m
2154  hil_gps.vel_ned_valid = true;
2155  hil_gps.cog_rad = ((gps.cog == 65535) ? NAN : wrap_2pi(math::radians(gps.cog * 1e-2f)));
2156 
2157  hil_gps.fix_type = gps.fix_type;
2158  hil_gps.satellites_used = gps.satellites_visible; //TODO: rename mavlink_hil_gps_t sats visible to used?
2159 
2160  hil_gps.heading = NAN;
2161  hil_gps.heading_offset = NAN;
2162 
2163  _gps_pub.publish(hil_gps);
2164 }
2165 
2166 void
2168 {
2169  mavlink_follow_target_t follow_target_msg;
2170  mavlink_msg_follow_target_decode(msg, &follow_target_msg);
2171 
2172  follow_target_s follow_target_topic{};
2173 
2174  follow_target_topic.timestamp = hrt_absolute_time();
2175  follow_target_topic.lat = follow_target_msg.lat * 1e-7;
2176  follow_target_topic.lon = follow_target_msg.lon * 1e-7;
2177  follow_target_topic.alt = follow_target_msg.alt;
2178 
2179  _follow_target_pub.publish(follow_target_topic);
2180 }
2181 
2182 void
2184 {
2185  mavlink_landing_target_t landing_target;
2186  mavlink_msg_landing_target_decode(msg, &landing_target);
2187 
2188  if (landing_target.position_valid && landing_target.frame == MAV_FRAME_LOCAL_NED) {
2189  landing_target_pose_s landing_target_pose{};
2190 
2191  landing_target_pose.timestamp = _mavlink_timesync.sync_stamp(landing_target.time_usec);
2192  landing_target_pose.abs_pos_valid = true;
2193  landing_target_pose.x_abs = landing_target.x;
2194  landing_target_pose.y_abs = landing_target.y;
2195  landing_target_pose.z_abs = landing_target.z;
2196 
2197  _landing_target_pose_pub.publish(landing_target_pose);
2198  }
2199 }
2200 
2201 void
2203 {
2204  mavlink_cellular_status_t status;
2205  mavlink_msg_cellular_status_decode(msg, &status);
2206 
2207  cellular_status_s cellular_status{};
2208 
2209  cellular_status.timestamp = hrt_absolute_time();
2210  cellular_status.status = status.status;
2211  cellular_status.type = status.type;
2212  cellular_status.quality = status.quality;
2213  cellular_status.mcc = status.mcc;
2214  cellular_status.mnc = status.mnc;
2215  cellular_status.lac = status.lac;
2216  cellular_status.cid = status.cid;
2217 
2218  _cellular_status_pub.publish(cellular_status);
2219 }
2220 
2221 void
2223 {
2224  mavlink_adsb_vehicle_t adsb;
2225  mavlink_msg_adsb_vehicle_decode(msg, &adsb);
2226 
2228 
2230 
2231  t.icao_address = adsb.ICAO_address;
2232  t.lat = adsb.lat * 1e-7;
2233  t.lon = adsb.lon * 1e-7;
2234  t.altitude_type = adsb.altitude_type;
2235  t.altitude = adsb.altitude / 1000.0f;
2236  t.heading = adsb.heading / 100.0f / 180.0f * M_PI_F - M_PI_F;
2237  t.hor_velocity = adsb.hor_velocity / 100.0f;
2238  t.ver_velocity = adsb.ver_velocity / 100.0f;
2239  memcpy(&t.callsign[0], &adsb.callsign[0], sizeof(t.callsign));
2240  t.emitter_type = adsb.emitter_type;
2241  t.tslc = adsb.tslc;
2242  t.squawk = adsb.squawk;
2243 
2244  t.flags = transponder_report_s::PX4_ADSB_FLAGS_RETRANSLATE; //Unset in receiver already broadcast its messages
2245 
2246  if (adsb.flags & ADSB_FLAGS_VALID_COORDS) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS; }
2247 
2248  if (adsb.flags & ADSB_FLAGS_VALID_ALTITUDE) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE; }
2249 
2250  if (adsb.flags & ADSB_FLAGS_VALID_HEADING) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING; }
2251 
2252  if (adsb.flags & ADSB_FLAGS_VALID_VELOCITY) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY; }
2253 
2254  if (adsb.flags & ADSB_FLAGS_VALID_CALLSIGN) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_CALLSIGN; }
2255 
2256  if (adsb.flags & ADSB_FLAGS_VALID_SQUAWK) { t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_SQUAWK; }
2257 
2258  //PX4_INFO("code: %d callsign: %s, vel: %8.4f, tslc: %d", (int)t.ICAO_address, t.callsign, (double)t.hor_velocity, (int)t.tslc);
2259 
2261 }
2262 
2263 void
2265 {
2266  mavlink_utm_global_position_t utm_pos;
2267  mavlink_msg_utm_global_position_decode(msg, &utm_pos);
2268 
2269  // Convert cm/s to m/s
2270  float vx = utm_pos.vx / 100.0f;
2271  float vy = utm_pos.vy / 100.0f;
2272  float vz = utm_pos.vz / 100.0f;
2273 
2276  // TODO: ID
2277  t.lat = utm_pos.lat * 1e-7;
2278  t.lon = utm_pos.lon * 1e-7;
2279  t.altitude = utm_pos.alt / 1000.0f;
2280  t.altitude_type = ADSB_ALTITUDE_TYPE_GEOMETRIC;
2281  // UTM_GLOBAL_POSIION uses NED (north, east, down) coordinates for velocity, in cm / s.
2282  t.heading = atan2f(vy, vx);
2283  t.hor_velocity = sqrtf(vy * vy + vx * vx);
2284  t.ver_velocity = -vz;
2285  // TODO: Callsign
2286  // For now, set it to all 0s. This is a null-terminated string, so not explicitly giving it a null
2287  // terminator could cause problems.
2288  memset(&t.callsign[0], 0, sizeof(t.callsign));
2289  t.emitter_type = ADSB_EMITTER_TYPE_NO_INFO; // TODO: Is this correct?
2290 
2291  // The Mavlink docs do not specify what to do if tslc (time since last communication) is out of range of
2292  // an 8-bit int, or if this is the first communication.
2293  // Here, I assume that if this is the first communication, tslc = 0.
2294  // If tslc > 255, then tslc = 255.
2295  unsigned long time_passed = (t.timestamp - _last_utm_global_pos_com) / 1000000;
2296 
2297  if (_last_utm_global_pos_com == 0) {
2298  time_passed = 0;
2299 
2300  } else if (time_passed > UINT8_MAX) {
2301  time_passed = UINT8_MAX;
2302  }
2303 
2304  t.tslc = (uint8_t) time_passed;
2305 
2306  t.flags = 0;
2307 
2308  if (utm_pos.flags & UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE) {
2309  t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_COORDS;
2310  }
2311 
2312  if (utm_pos.flags & UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE) {
2313  t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_ALTITUDE;
2314  }
2315 
2316  if (utm_pos.flags & UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE) {
2317  t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_HEADING;
2318  t.flags |= transponder_report_s::PX4_ADSB_FLAGS_VALID_VELOCITY;
2319  }
2320 
2321  // Note: t.flags has deliberately NOT set VALID_CALLSIGN or VALID_SQUAWK, because UTM_GLOBAL_POSITION does not
2322  // provide these.
2324 
2325  _last_utm_global_pos_com = t.timestamp;
2326 }
2327 
2328 void
2330 {
2331  mavlink_collision_t collision;
2332  mavlink_msg_collision_decode(msg, &collision);
2333 
2334  collision_report_s collision_report{};
2335 
2336  collision_report.timestamp = hrt_absolute_time();
2337  collision_report.src = collision.src;
2338  collision_report.id = collision.id;
2339  collision_report.action = collision.action;
2340  collision_report.threat_level = collision.threat_level;
2341  collision_report.time_to_minimum_delta = collision.time_to_minimum_delta;
2342  collision_report.altitude_minimum_delta = collision.altitude_minimum_delta;
2343  collision_report.horizontal_minimum_delta = collision.horizontal_minimum_delta;
2344 
2345  _collision_report_pub.publish(collision_report);
2346 }
2347 
2348 void
2350 {
2351  mavlink_gps_rtcm_data_t gps_rtcm_data_msg;
2352  mavlink_msg_gps_rtcm_data_decode(msg, &gps_rtcm_data_msg);
2353 
2354  gps_inject_data_s gps_inject_data_topic{};
2355 
2356  gps_inject_data_topic.len = math::min((int)sizeof(gps_rtcm_data_msg.data),
2357  (int)sizeof(uint8_t) * gps_rtcm_data_msg.len);
2358  gps_inject_data_topic.flags = gps_rtcm_data_msg.flags;
2359  memcpy(gps_inject_data_topic.data, gps_rtcm_data_msg.data,
2360  math::min((int)sizeof(gps_inject_data_topic.data), (int)sizeof(uint8_t) * gps_inject_data_topic.len));
2361 
2362  _gps_inject_data_pub.publish(gps_inject_data_topic);
2363 }
2364 
2365 void
2367 {
2368  mavlink_hil_state_quaternion_t hil_state;
2369  mavlink_msg_hil_state_quaternion_decode(msg, &hil_state);
2370 
2371  const uint64_t timestamp = hrt_absolute_time();
2372 
2373  /* airspeed */
2374  {
2375  airspeed_s airspeed{};
2376 
2377  airspeed.timestamp = timestamp;
2378  airspeed.indicated_airspeed_m_s = hil_state.ind_airspeed * 1e-2f;
2379  airspeed.true_airspeed_m_s = hil_state.true_airspeed * 1e-2f;
2380 
2381  _airspeed_pub.publish(airspeed);
2382  }
2383 
2384  /* attitude */
2385  {
2386  vehicle_attitude_s hil_attitude{};
2387 
2388  hil_attitude.timestamp = timestamp;
2389 
2390  matrix::Quatf q(hil_state.attitude_quaternion);
2391  q.copyTo(hil_attitude.q);
2392 
2393  _attitude_pub.publish(hil_attitude);
2394  }
2395 
2396  /* global position */
2397  {
2398  vehicle_global_position_s hil_global_pos{};
2399 
2400  hil_global_pos.timestamp = timestamp;
2401  hil_global_pos.lat = hil_state.lat / ((double)1e7);
2402  hil_global_pos.lon = hil_state.lon / ((double)1e7);
2403  hil_global_pos.alt = hil_state.alt / 1000.0f;
2404  hil_global_pos.vel_n = hil_state.vx / 100.0f;
2405  hil_global_pos.vel_e = hil_state.vy / 100.0f;
2406  hil_global_pos.vel_d = hil_state.vz / 100.0f;
2407  hil_global_pos.eph = 2.0f;
2408  hil_global_pos.epv = 4.0f;
2409 
2410  _global_pos_pub.publish(hil_global_pos);
2411  }
2412 
2413  /* local position */
2414  {
2415  double lat = hil_state.lat * 1e-7;
2416  double lon = hil_state.lon * 1e-7;
2417 
2418  if (!_hil_local_proj_inited) {
2419  _hil_local_proj_inited = true;
2420  _hil_local_alt0 = hil_state.alt / 1000.0f;
2421 
2423  }
2424 
2425  float x = 0.0f;
2426  float y = 0.0f;
2427  map_projection_project(&_hil_local_proj_ref, lat, lon, &x, &y);
2428 
2429  vehicle_local_position_s hil_local_pos{};
2430  hil_local_pos.timestamp = timestamp;
2431 
2432  hil_local_pos.ref_timestamp = _hil_local_proj_ref.timestamp;
2433  hil_local_pos.ref_lat = math::radians(_hil_local_proj_ref.lat_rad);
2434  hil_local_pos.ref_lon = math::radians(_hil_local_proj_ref.lon_rad);
2435  hil_local_pos.ref_alt = _hil_local_alt0;
2436  hil_local_pos.xy_valid = true;
2437  hil_local_pos.z_valid = true;
2438  hil_local_pos.v_xy_valid = true;
2439  hil_local_pos.v_z_valid = true;
2440  hil_local_pos.x = x;
2441  hil_local_pos.y = y;
2442  hil_local_pos.z = _hil_local_alt0 - hil_state.alt / 1000.0f;
2443  hil_local_pos.vx = hil_state.vx / 100.0f;
2444  hil_local_pos.vy = hil_state.vy / 100.0f;
2445  hil_local_pos.vz = hil_state.vz / 100.0f;
2446 
2447  matrix::Eulerf euler{matrix::Quatf(hil_state.attitude_quaternion)};
2448  hil_local_pos.yaw = euler.psi();
2449  hil_local_pos.xy_global = true;
2450  hil_local_pos.z_global = true;
2451  hil_local_pos.vxy_max = INFINITY;
2452  hil_local_pos.vz_max = INFINITY;
2453  hil_local_pos.hagl_min = INFINITY;
2454  hil_local_pos.hagl_max = INFINITY;
2455 
2456  _local_pos_pub.publish(hil_local_pos);
2457  }
2458 
2459  /* accelerometer */
2460  {
2461  sensor_accel_s accel{};
2462 
2463  accel.timestamp = timestamp;
2464  accel.x_raw = hil_state.xacc / CONSTANTS_ONE_G * 1e3f;
2465  accel.y_raw = hil_state.yacc / CONSTANTS_ONE_G * 1e3f;
2466  accel.z_raw = hil_state.zacc / CONSTANTS_ONE_G * 1e3f;
2467  accel.x = hil_state.xacc;
2468  accel.y = hil_state.yacc;
2469  accel.z = hil_state.zacc;
2470  accel.temperature = 25.0f;
2471 
2472  _accel_pub.publish(accel);
2473  }
2474 
2475  /* gyroscope */
2476  {
2477  sensor_gyro_s gyro{};
2478 
2479  gyro.timestamp = timestamp;
2480  gyro.x_raw = hil_state.rollspeed * 1e3f;
2481  gyro.y_raw = hil_state.pitchspeed * 1e3f;
2482  gyro.z_raw = hil_state.yawspeed * 1e3f;
2483  gyro.x = hil_state.rollspeed;
2484  gyro.y = hil_state.pitchspeed;
2485  gyro.z = hil_state.yawspeed;
2486  gyro.temperature = 25.0f;
2487 
2488  _gyro_pub.publish(gyro);
2489  }
2490 
2491  /* battery status */
2492  {
2493  battery_status_s hil_battery_status{};
2494 
2495  hil_battery_status.timestamp = timestamp;
2496  hil_battery_status.voltage_v = 11.1f;
2497  hil_battery_status.voltage_filtered_v = 11.1f;
2498  hil_battery_status.current_a = 10.0f;
2499  hil_battery_status.discharged_mah = -1.0f;
2500 
2501  _battery_pub.publish(hil_battery_status);
2502  }
2503 }
2504 
2505 void
2507 {
2508  mavlink_named_value_float_t debug_msg;
2509  mavlink_msg_named_value_float_decode(msg, &debug_msg);
2510 
2511  debug_key_value_s debug_topic{};
2512 
2513  debug_topic.timestamp = hrt_absolute_time();
2514  memcpy(debug_topic.key, debug_msg.name, sizeof(debug_topic.key));
2515  debug_topic.key[sizeof(debug_topic.key) - 1] = '\0'; // enforce null termination
2516  debug_topic.value = debug_msg.value;
2517 
2518  _debug_key_value_pub.publish(debug_topic);
2519 }
2520 
2521 void
2523 {
2524  mavlink_debug_t debug_msg;
2525  mavlink_msg_debug_decode(msg, &debug_msg);
2526 
2527  debug_value_s debug_topic{};
2528 
2529  debug_topic.timestamp = hrt_absolute_time();
2530  debug_topic.ind = debug_msg.ind;
2531  debug_topic.value = debug_msg.value;
2532 
2533  _debug_value_pub.publish(debug_topic);
2534 }
2535 
2536 void
2538 {
2539  mavlink_debug_vect_t debug_msg;
2540  mavlink_msg_debug_vect_decode(msg, &debug_msg);
2541 
2542  debug_vect_s debug_topic{};
2543 
2544  debug_topic.timestamp = hrt_absolute_time();
2545  memcpy(debug_topic.name, debug_msg.name, sizeof(debug_topic.name));
2546  debug_topic.name[sizeof(debug_topic.name) - 1] = '\0'; // enforce null termination
2547  debug_topic.x = debug_msg.x;
2548  debug_topic.y = debug_msg.y;
2549  debug_topic.z = debug_msg.z;
2550 
2551  _debug_vect_pub.publish(debug_topic);
2552 }
2553 
2554 void
2556 {
2557  mavlink_debug_float_array_t debug_msg;
2558  mavlink_msg_debug_float_array_decode(msg, &debug_msg);
2559 
2560  debug_array_s debug_topic{};
2561 
2562  debug_topic.timestamp = hrt_absolute_time();
2563  debug_topic.id = debug_msg.array_id;
2564  memcpy(debug_topic.name, debug_msg.name, sizeof(debug_topic.name));
2565  debug_topic.name[sizeof(debug_topic.name) - 1] = '\0'; // enforce null termination
2566 
2567  for (size_t i = 0; i < debug_array_s::ARRAY_SIZE; i++) {
2568  debug_topic.data[i] = debug_msg.data[i];
2569  }
2570 
2571  _debug_array_pub.publish(debug_topic);
2572 }
2573 
2574 void
2576 {
2577  mavlink_onboard_computer_status_t status_msg;
2578  mavlink_msg_onboard_computer_status_decode(msg, &status_msg);
2579 
2580  onboard_computer_status_s onboard_computer_status_topic{};
2581 
2582  onboard_computer_status_topic.timestamp = hrt_absolute_time();
2583  onboard_computer_status_topic.uptime = status_msg.uptime;
2584 
2585  onboard_computer_status_topic.type = status_msg.type;
2586 
2587  memcpy(onboard_computer_status_topic.cpu_cores, status_msg.cpu_cores, sizeof(status_msg.cpu_cores));
2588  memcpy(onboard_computer_status_topic.cpu_combined, status_msg.cpu_combined, sizeof(status_msg.cpu_combined));
2589  memcpy(onboard_computer_status_topic.gpu_cores, status_msg.gpu_cores, sizeof(status_msg.gpu_cores));
2590  memcpy(onboard_computer_status_topic.gpu_combined, status_msg.gpu_combined, sizeof(status_msg.gpu_combined));
2591  onboard_computer_status_topic.temperature_board = status_msg.temperature_board;
2592  memcpy(onboard_computer_status_topic.temperature_core, status_msg.temperature_core,
2593  sizeof(status_msg.temperature_core));
2594  memcpy(onboard_computer_status_topic.fan_speed, status_msg.fan_speed, sizeof(status_msg.fan_speed));
2595  onboard_computer_status_topic.ram_usage = status_msg.ram_usage;
2596  onboard_computer_status_topic.ram_total = status_msg.ram_total;
2597  memcpy(onboard_computer_status_topic.storage_type, status_msg.storage_type, sizeof(status_msg.storage_type));
2598  memcpy(onboard_computer_status_topic.storage_usage, status_msg.storage_usage, sizeof(status_msg.storage_usage));
2599  memcpy(onboard_computer_status_topic.storage_total, status_msg.storage_total, sizeof(status_msg.storage_total));
2600  memcpy(onboard_computer_status_topic.link_type, status_msg.link_type, sizeof(status_msg.link_type));
2601  memcpy(onboard_computer_status_topic.link_tx_rate, status_msg.link_tx_rate, sizeof(status_msg.link_tx_rate));
2602  memcpy(onboard_computer_status_topic.link_rx_rate, status_msg.link_rx_rate, sizeof(status_msg.link_rx_rate));
2603  memcpy(onboard_computer_status_topic.link_tx_max, status_msg.link_tx_max, sizeof(status_msg.link_tx_max));
2604  memcpy(onboard_computer_status_topic.link_rx_max, status_msg.link_rx_max, sizeof(status_msg.link_rx_max));
2605 
2606  _onboard_computer_status_pub.publish(onboard_computer_status_topic);
2607 }
2608 
2610 {
2611  if (msg->sysid == mavlink_system.sysid) {
2612  // log message from the same system
2613 
2614  mavlink_statustext_t statustext;
2615  mavlink_msg_statustext_decode(msg, &statustext);
2616 
2617  log_message_s log_message{};
2618 
2619  log_message.severity = statustext.severity;
2620  log_message.timestamp = hrt_absolute_time();
2621 
2622  snprintf(log_message.text, sizeof(log_message.text),
2623  "[mavlink: component %d] %." STRINGIFY(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN) "s", msg->compid, statustext.text);
2624 
2625  _log_message_pub.publish(log_message);
2626  }
2627 }
2628 
2629 /**
2630  * Receive data from UART/UDP
2631  */
2632 void
2634 {
2635  /* set thread name */
2636  {
2637  char thread_name[17];
2638  snprintf(thread_name, sizeof(thread_name), "mavlink_rcv_if%d", _mavlink->get_instance_id());
2639  px4_prctl(PR_SET_NAME, thread_name, px4_getpid());
2640  }
2641 
2642  // make sure mavlink app has booted before we start processing anything (parameter sync, etc)
2643  while (!_mavlink->boot_complete()) {
2645  PX4_ERR("system boot did not complete in 20 seconds");
2647  }
2648 
2649  px4_usleep(100000);
2650  }
2651 
2652  // poll timeout in ms. Also defines the max update frequency of the mission & param manager, etc.
2653  const int timeout = 10;
2654 
2655 #if defined(__PX4_POSIX)
2656  /* 1500 is the Wifi MTU, so we make sure to fit a full packet */
2657  uint8_t buf[1600 * 5];
2658 #elif defined(CONFIG_NET)
2659  /* 1500 is the Wifi MTU, so we make sure to fit a full packet */
2660  uint8_t buf[1000];
2661 #else
2662  /* the serial port buffers internally as well, we just need to fit a small chunk */
2663  uint8_t buf[64];
2664 #endif
2665  mavlink_message_t msg;
2666 
2667  struct pollfd fds[1] = {};
2668 
2670  fds[0].fd = _mavlink->get_uart_fd();
2671  fds[0].events = POLLIN;
2672  }
2673 
2674 #if defined(MAVLINK_UDP)
2675  struct sockaddr_in srcaddr = {};
2676  socklen_t addrlen = sizeof(srcaddr);
2677 
2678  if (_mavlink->get_protocol() == Protocol::UDP) {
2679  fds[0].fd = _mavlink->get_socket_fd();
2680  fds[0].events = POLLIN;
2681  }
2682 
2683 #endif // MAVLINK_UDP
2684 
2685  ssize_t nread = 0;
2686  hrt_abstime last_send_update = 0;
2687 
2688  while (!_mavlink->_task_should_exit) {
2689 
2690  // check for parameter updates
2692  // clear update
2693  parameter_update_s pupdate;
2694  _parameter_update_sub.copy(&pupdate);
2695 
2696  // update parameters from storage
2697  updateParams();
2698  }
2699 
2700  if (poll(&fds[0], 1, timeout) > 0) {
2702 
2703  /*
2704  * to avoid reading very small chunks wait for data before reading
2705  * this is designed to target one message, so >20 bytes at a time
2706  */
2707  const unsigned character_count = 20;
2708 
2709  /* non-blocking read. read may return negative values */
2710  if ((nread = ::read(fds[0].fd, buf, sizeof(buf))) < (ssize_t)character_count) {
2711  const unsigned sleeptime = character_count * 1000000 / (_mavlink->get_baudrate() / 10);
2712  px4_usleep(sleeptime);
2713  }
2714  }
2715 
2716 #if defined(MAVLINK_UDP)
2717 
2718  else if (_mavlink->get_protocol() == Protocol::UDP) {
2719  if (fds[0].revents & POLLIN) {
2720  nread = recvfrom(_mavlink->get_socket_fd(), buf, sizeof(buf), 0, (struct sockaddr *)&srcaddr, &addrlen);
2721  }
2722 
2723  struct sockaddr_in &srcaddr_last = _mavlink->get_client_source_address();
2724 
2725  int localhost = (127 << 24) + 1;
2726 
2727  if (!_mavlink->get_client_source_initialized()) {
2728 
2729  // set the address either if localhost or if 3 seconds have passed
2730  // this ensures that a GCS running on localhost can get a hold of
2731  // the system within the first N seconds
2732  hrt_abstime stime = _mavlink->get_start_time();
2733 
2734  if ((stime != 0 && (hrt_elapsed_time(&stime) > 3_s))
2735  || (srcaddr_last.sin_addr.s_addr == htonl(localhost))) {
2736 
2737  srcaddr_last.sin_addr.s_addr = srcaddr.sin_addr.s_addr;
2738  srcaddr_last.sin_port = srcaddr.sin_port;
2739 
2740  _mavlink->set_client_source_initialized();
2741 
2742  PX4_INFO("partner IP: %s", inet_ntoa(srcaddr.sin_addr));
2743  }
2744  }
2745  }
2746 
2747  // only start accepting messages on UDP once we're sure who we talk to
2748  if (_mavlink->get_protocol() != Protocol::UDP || _mavlink->get_client_source_initialized()) {
2749 #endif // MAVLINK_UDP
2750 
2751  /* if read failed, this loop won't execute */
2752  for (ssize_t i = 0; i < nread; i++) {
2753  if (mavlink_parse_char(_mavlink->get_channel(), buf[i], &msg, &_status)) {
2754 
2755  /* check if we received version 2 and request a switch. */
2756  if (!(_mavlink->get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) {
2757  /* this will only switch to proto version 2 if allowed in settings */
2759  }
2760 
2761  /* handle generic messages and commands */
2762  handle_message(&msg);
2763 
2764  /* handle packet with mission manager */
2766 
2767 
2768  /* handle packet with parameter component */
2770 
2771  if (_mavlink->ftp_enabled()) {
2772  /* handle packet with ftp component */
2774  }
2775 
2776  /* handle packet with log component */
2778 
2779  /* handle packet with timesync component */
2781 
2782  /* handle packet with parent object */
2783  _mavlink->handle_message(&msg);
2784  }
2785  }
2786 
2787  /* count received bytes (nread will be -1 on read error) */
2788  if (nread > 0) {
2789  _mavlink->count_rxbytes(nread);
2790  }
2791 
2792 #if defined(MAVLINK_UDP)
2793  }
2794 
2795 #endif // MAVLINK_UDP
2796  }
2797 
2799 
2800  if (t - last_send_update > timeout * 1000) {
2803 
2805 
2806  if (_mavlink->ftp_enabled()) {
2807  _mavlink_ftp.send(t);
2808  }
2809 
2811  last_send_update = t;
2812  }
2813 
2814  }
2815 }
2816 
2817 void *
2819 {
2820  MavlinkReceiver rcv{(Mavlink *)context};
2821  rcv.Run();
2822 
2823  return nullptr;
2824 }
2825 
2826 void
2827 MavlinkReceiver::receive_start(pthread_t *thread, Mavlink *parent)
2828 {
2829  pthread_attr_t receiveloop_attr;
2830  pthread_attr_init(&receiveloop_attr);
2831 
2832  struct sched_param param;
2833  (void)pthread_attr_getschedparam(&receiveloop_attr, &param);
2834  param.sched_priority = SCHED_PRIORITY_MAX - 80;
2835  (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
2836 
2837  pthread_attr_setstacksize(&receiveloop_attr,
2838  PX4_STACK_ADJUSTED(sizeof(MavlinkReceiver) + 2840 + MAVLINK_RECEIVER_NET_ADDED_STACK));
2839 
2840  pthread_create(thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);
2841 
2842  pthread_attr_destroy(&receiveloop_attr);
2843 }
#define VEHICLE_TYPE_FIXED_WING
constexpr _Tp constrain(_Tp val, _Tp min_val, _Tp max_val)
Definition: Limits.hpp:66
int globallocalconverter_init(double lat_0, double lon_0, float alt_0, uint64_t timestamp)
Initialize the global mapping between global position (spherical) and local position (NED)...
Definition: geo.cpp:211
R/C input interface.
uint64_t timestamp
Definition: sensor_accel.h:53
static struct vehicle_status_s status
Definition: Commander.cpp:138
Definition of geo / math functions to perform geodesic calculations.
float calc_TAS_from_EAS(float speed_equivalent, float pressure_ambient, float temperature_celsius)
Calculate true airspeed (TAS) from equivalent airspeed (EAS).
Definition: airspeed.cpp:218
Dcm< float > Dcmf
Definition: Dcm.hpp:185
__EXPORT void rotate_3f(enum Rotation rot, float &x, float &y, float &z)
rotate a 3 element float vector in-place
Definition: rotation.cpp:63
bool publish(const T &data)
Publish the struct.
A set of useful macros for enhanced runtime and compile time error detection and warning suppression...
void normalize()
Definition: Vector.hpp:87
float calc_IAS(float differential_pressure)
Calculate indicated airspeed (IAS).
Definition: airspeed.cpp:195
uint64_t timestamp
Definition: input_rc.h:69
void copyTo(Type dst[M *N]) const
Definition: Matrix.hpp:115
Definition: ping.h:51
Vector rotation library.
Quaternion class.
Definition: Dcm.hpp:24
static constexpr float CONSTANTS_ONE_G
Definition: geo.h:51
Type wrap_2pi(Type x)
Wrap value in range [0, 2Ï€)
uint64_t timestamp
Definition: geo.h:76
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
static void read(bootloader_app_shared_t *pshared)
bool publish(const T &data)
Publish the struct.
Definition: Publication.hpp:68
ssize_t px4_write(int fd, const void *buffer, size_t buflen)
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint8_t switch_pos_t
Definition: uORB.h:261
constexpr T radians(T degrees)
Definition: Limits.hpp:85
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
Definition: drv_hrt.h:102
uint64_t timestamp
Definition: debug_vect.h:53
#define TONE_ALARM0_DEVICE_PATH
Euler angles class.
Definition: AxisAngle.hpp:18
uint64_t timestamp
Definition: sensor_gyro.h:53
bool updated()
Check if there is a new update.
uint64_t timestamp
Definition: debug_value.h:53
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Driver for the PX4 audio alarm port, /dev/tone_alarm.
int fd
Definition: dataman.cpp:146
constexpr _Tp min(_Tp a, _Tp b)
Definition: Limits.hpp:54
uint64_t timestamp
Definition: ping.h:53
uint64_t timestamp
Definition: debug_array.h:54
#define RC_INPUT_RSSI_MAX
Maximum RSSI value.
Definition: drv_rc_input.h:64
uint64_t timestamp
Definition: sensor_mag.h:53
int px4_open(const char *path, int flags,...)
#define STRINGIFY(s)
Definition: px4_macros.h:94
uint64_t timestamp
Definition: airspeed.h:53
int globallocalconverter_tolocal(double lat, double lon, float alt, float *x, float *y, float *z)
Convert from global position coordinates to local position coordinates using the global reference...
Definition: geo.cpp:229
static float actuator_controls[output_max]
Quaternion< float > Quatf
Definition: Quaternion.hpp:544
int map_projection_project(const struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y)
Definition: geo.cpp:132
PX4 custom flight modes.
#define ORB_MULTI_MAX_INSTANCES
Maximum number of multi topic instances.
Definition: uORB.h:62
float calc_EAS_from_IAS(float speed_indicated, float scale)
Calculate equivalent airspeed (EAS) from indicated airspeed (IAS).
Definition: airspeed.cpp:232
bool globallocalconverter_initialized()
Checks if globallocalconverter was initialized.
Definition: geo.cpp:224
#define M_PI_F
Definition: ashtech.cpp:44
uint64_t timestamp
Definition: sensor_baro.h:53
uint64_t timestamp
Definition: follow_target.h:53
bool publish(const T &data)
Publish the struct.
int map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0)
Initializes the map transformation given by the argument and sets the timestamp to now...
Definition: geo.cpp:105
uint8_t severity
Definition: log_message.h:54
bool copy(void *dst)
Copy the struct.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
int px4_close(int fd)