APM:Libraries
GCS_Common.cpp
Go to the documentation of this file.
1 /*
2  Common GCS MAVLink functions for all vehicle types
3 
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include <AP_AHRS/AP_AHRS.h>
18 #include <AP_HAL/AP_HAL.h>
20 #include <AP_Vehicle/AP_Vehicle.h>
23 
24 #include "GCS.h"
25 
26 #include <stdio.h>
27 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
28 #include <drivers/drv_pwm_output.h>
29 #include <sys/types.h>
30 #include <sys/stat.h>
31 #include <fcntl.h>
32 #endif
33 
34 #if HAL_RCINPUT_WITH_AP_RADIO
35 #include <AP_Radio/AP_Radio.h>
37 #endif
38 
39 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
40 #include <SITL/SITL.h>
41 #endif
42 
43 extern const AP_HAL::HAL& hal;
44 
46 uint8_t GCS_MAVLINK::mavlink_active = 0;
49 
50 GCS *GCS::_singleton = nullptr;
51 
53 {
55 }
56 
57 void
58 GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
59 {
60  if (!valid_channel(mav_chan)) {
61  return;
62  }
63 
64  _port = port;
65  chan = mav_chan;
66 
68  _queued_parameter = nullptr;
69 
70  snprintf(_perf_packet_name, sizeof(_perf_packet_name), "GCS_Packet_%u", chan);
72 
73  snprintf(_perf_update_name, sizeof(_perf_update_name), "GCS_Update_%u", chan);
75 
76  initialised = true;
77 }
78 
79 
80 /*
81  setup a UART, handling begin() and init()
82  */
83 void
85 {
87 
88  // search for serial port
89 
90  AP_HAL::UARTDriver *uart;
91  uart = serial_manager.find_serial(protocol, instance);
92  if (uart == nullptr) {
93  // return immediately if not found
94  return;
95  }
96 
97  // get associated mavlink channel
98  mavlink_channel_t mav_chan;
99  if (!serial_manager.get_mavlink_channel(protocol, instance, mav_chan)) {
100  // return immediately in unlikely case mavlink channel cannot be found
101  return;
102  }
103 
104  /*
105  Now try to cope with SiK radios that may be stuck in bootloader
106  mode because CTS was held while powering on. This tells the
107  bootloader to wait for a firmware. It affects any SiK radio with
108  CTS connected that is externally powered. To cope we send 0x30
109  0x20 at 115200 on startup, which tells the bootloader to reset
110  and boot normally
111  */
112  uart->begin(115200);
113  AP_HAL::UARTDriver::flow_control old_flow_control = uart->get_flow_control();
115  for (uint8_t i=0; i<3; i++) {
116  hal.scheduler->delay(1);
117  uart->write(0x30);
118  uart->write(0x20);
119  }
120  // since tcdrain() and TCSADRAIN may not be implemented...
121  hal.scheduler->delay(1);
122 
123  uart->set_flow_control(old_flow_control);
124 
125  // now change back to desired baudrate
126  uart->begin(serial_manager.find_baudrate(protocol, instance));
127 
128  // and init the gcs instance
129  init(uart, mav_chan);
130 
132  mavlink_status_t *status = mavlink_get_channel_status(chan);
133  if (status == nullptr) {
134  return;
135  }
136 
137  if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2) {
138  // load signing key
140 
141  if (status->signing == nullptr) {
142  // if signing is off start by sending MAVLink1.
143  status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
144  }
145  // announce that we are MAVLink2 capable
146  hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MAVLINK2);
147  } else if (status) {
148  // user has asked to only send MAVLink1
149  status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
150  }
151 
152  if (chan == MAVLINK_COMM_0) {
153  // Always start with MAVLink1 on first port for now, to allow for recovery
154  // after experiments with MAVLink2
155  status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
156  }
157 }
158 
159 
164 void
166 {
167  if (initialised &&
170  mavlink_msg_mission_request_send(
171  chan,
175  MAV_MISSION_TYPE_MISSION);
176  }
177 }
178 
180 {
181  unsigned __brkval = 0;
182  uint32_t memory = hal.util->available_memory();
183  mavlink_msg_meminfo_send(chan, __brkval, MIN(memory, 0xFFFFU), memory);
184 }
185 
186 // report power supply status
188 {
189  mavlink_msg_power_status_send(chan,
190  hal.analogin->board_voltage() * 1000,
191  hal.analogin->servorail_voltage() * 1000,
193 }
194 
196  const uint8_t instance) const
197 {
198  // catch the battery backend not supporting the required number of cells
199  static_assert(sizeof(AP_BattMonitor::cells) >= (sizeof(uint16_t) * MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN),
200  "Not enough battery cells for the MAVLink message");
201 
202  float temp;
203  bool got_temperature = battery.get_temperature(temp, instance);
204  mavlink_msg_battery_status_send(chan,
205  instance, // id
206  MAV_BATTERY_FUNCTION_UNKNOWN, // function
207  MAV_BATTERY_TYPE_UNKNOWN, // type
208  got_temperature ? ((int16_t) (temp * 100)) : INT16_MAX, // temperature. INT16_MAX if unknown
209  battery.get_cell_voltages(instance).cells, // cell voltages
210  battery.has_current(instance) ? battery.current_amps(instance) * 100 : -1, // current in centiampere
211  battery.has_current(instance) ? battery.consumed_mah(instance) : -1, // total consumed current in milliampere.hour
212  battery.has_consumed_energy(instance) ? battery.consumed_wh(instance) * 36 : -1, // consumed energy in hJ (hecto-Joules)
213  battery.capacity_remaining_pct(instance));
214 }
215 
216 // returns true if all battery instances were reported
218 {
220 
221  for(uint8_t i = 0; i < battery.num_instances(); i++) {
222  CHECK_PAYLOAD_SIZE(BATTERY_STATUS);
223  send_battery_status(battery, i);
224  }
225  return true;
226 }
227 
228 void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor, const uint8_t instance) const
229 {
230  if (!sensor->has_data()) {
231  return;
232  }
233 
234  mavlink_msg_distance_sensor_send(
235  chan,
236  AP_HAL::millis(), // time since system boot TODO: take time of measurement
237  sensor->min_distance_cm(), // minimum distance the sensor can measure in centimeters
238  sensor->max_distance_cm(), // maximum distance the sensor can measure in centimeters
239  sensor->distance_cm(), // current distance reading
240  sensor->get_mav_distance_sensor_type(), // type from MAV_DISTANCE_SENSOR enum
241  instance, // onboard ID of the sensor == instance
242  sensor->orientation(), // direction the sensor faces from MAV_SENSOR_ORIENTATION enum
243  0); // Measurement covariance in centimeters, 0 for unknown / invalid readings
244 }
245 
247 {
248  RangeFinder *rangefinder = RangeFinder::get_singleton();
249  if (rangefinder == nullptr) {
250  return true; // this is wrong, but pretend we sent data and don't requeue
251  }
252 
253  // if we have a proximity backend that utilizes rangefinders cull sending them here,
254  // and allow the later proximity code to manage them
255  bool filter_possible_proximity_sensors = false;
257  if (proximity != nullptr) {
258  for (uint8_t i = 0; i < proximity->num_sensors(); i++) {
259  if (proximity->get_type(i) == AP_Proximity::Proximity_Type_RangeFinder) {
260  filter_possible_proximity_sensors = true;
261  }
262  }
263  }
264 
265  for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
266  CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
267  AP_RangeFinder_Backend *sensor = rangefinder->get_backend(i);
268  if (sensor == nullptr) {
269  continue;
270  }
271  enum Rotation orient = sensor->orientation();
272  if (!filter_possible_proximity_sensors ||
273  (orient > ROTATION_YAW_315 && orient != ROTATION_PITCH_90)) {
274  send_distance_sensor(sensor, i);
275  }
276  }
277  return true;
278 }
279 
281 {
282  RangeFinder *rangefinder = RangeFinder::get_singleton();
283  if (rangefinder == nullptr) {
284  return;
285  }
287  if (s == nullptr) {
288  return;
289  }
290  mavlink_msg_rangefinder_send(
291  chan,
292  s->distance_cm() * 0.01f,
293  s->voltage_mv() * 0.001f);
294 }
295 
297 {
299  if (proximity == nullptr || proximity->get_status() == AP_Proximity::Proximity_NotConnected) {
300  return true; // this is wrong, but pretend we sent data and don't requeue
301  }
302 
303  const uint16_t dist_min = (uint16_t)(proximity->distance_min() * 100.0f); // minimum distance the sensor can measure in centimeters
304  const uint16_t dist_max = (uint16_t)(proximity->distance_max() * 100.0f); // maximum distance the sensor can measure in centimeters
305  // send horizontal distances
307  if (proximity->get_horizontal_distances(dist_array)) {
308  for (uint8_t i = 0; i < PROXIMITY_MAX_DIRECTION; i++) {
309  CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
310  mavlink_msg_distance_sensor_send(
311  chan,
312  AP_HAL::millis(), // time since system boot
313  dist_min, // minimum distance the sensor can measure in centimeters
314  dist_max, // maximum distance the sensor can measure in centimeters
315  (uint16_t)(dist_array.distance[i] * 100.0f), // current distance reading
316  MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum
317  PROXIMITY_SENSOR_ID_START + i, // onboard ID of the sensor
318  dist_array.orientation[i], // direction the sensor faces from MAV_SENSOR_ORIENTATION enum
319  0); // Measurement covariance in centimeters, 0 for unknown / invalid readings
320  }
321  }
322 
323  // send upward distance
324  float dist_up;
325  if (proximity->get_upward_distance(dist_up)) {
326  CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
327  mavlink_msg_distance_sensor_send(
328  chan,
329  AP_HAL::millis(), // time since system boot
330  dist_min, // minimum distance the sensor can measure in centimeters
331  dist_max, // maximum distance the sensor can measure in centimeters
332  (uint16_t)(dist_up * 100.0f), // current distance reading
333  MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum
334  PROXIMITY_SENSOR_ID_START + PROXIMITY_MAX_DIRECTION + 1, // onboard ID of the sensor
335  MAV_SENSOR_ROTATION_PITCH_90, // direction upwards
336  0); // Measurement covariance in centimeters, 0 for unknown / invalid readings
337  }
338  return true;
339 }
340 
341 // report AHRS2 state
343 {
344 #if AP_AHRS_NAVEKF_AVAILABLE
345  const AP_AHRS &ahrs = AP::ahrs();
346  Vector3f euler;
347  struct Location loc {};
348  if (ahrs.get_secondary_attitude(euler)) {
349  mavlink_msg_ahrs2_send(chan,
350  euler.x,
351  euler.y,
352  euler.z,
353  loc.alt*1.0e-2f,
354  loc.lat,
355  loc.lng);
356  }
357  const AP_AHRS_NavEKF &_ahrs = reinterpret_cast<const AP_AHRS_NavEKF&>(ahrs);
358  const NavEKF2 &ekf2 = _ahrs.get_NavEKF2_const();
359  if (ekf2.activeCores() > 0 &&
360  HAVE_PAYLOAD_SPACE(chan, AHRS3)) {
361  ekf2.getLLH(loc);
362  ekf2.getEulerAngles(-1,euler);
363  mavlink_msg_ahrs3_send(chan,
364  euler.x,
365  euler.y,
366  euler.z,
367  loc.alt*1.0e-2f,
368  loc.lat,
369  loc.lng,
370  0, 0, 0, 0);
371  }
372 #endif
373 }
374 
375 /*
376  handle a MISSION_REQUEST_LIST mavlink packet
377  */
378 void GCS_MAVLINK::handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg)
379 {
380  // decode
381  mavlink_mission_request_list_t packet;
382  mavlink_msg_mission_request_list_decode(msg, &packet);
383 
384  // reply with number of commands in the mission. The GCS will then request each command separately
385  mavlink_msg_mission_count_send(chan,msg->sysid, msg->compid, mission.num_commands(),
386  MAV_MISSION_TYPE_MISSION);
387 
388  // set variables to help handle the expected sending of commands to the GCS
389  waypoint_receiving = false; // record that we are sending commands (i.e. not receiving)
390 }
391 
392 /*
393  handle a MISSION_REQUEST mavlink packet
394  */
395 void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t *msg)
396 {
398 
399  if (msg->msgid == MAVLINK_MSG_ID_MISSION_REQUEST_INT) {
400  // decode
401  mavlink_mission_request_int_t packet;
402  mavlink_msg_mission_request_int_decode(msg, &packet);
403 
404  // retrieve mission from eeprom
405  if (!mission.read_cmd_from_storage(packet.seq, cmd)) {
406  goto mission_item_send_failed;
407  }
408 
409  mavlink_mission_item_int_t ret_packet;
410  memset(&ret_packet, 0, sizeof(ret_packet));
411  if (!AP_Mission::mission_cmd_to_mavlink_int(cmd, ret_packet)) {
412  goto mission_item_send_failed;
413  }
414 
415  // set packet's current field to 1 if this is the command being executed
416  if (cmd.id == (uint16_t)mission.get_current_nav_cmd().index) {
417  ret_packet.current = 1;
418  } else {
419  ret_packet.current = 0;
420  }
421 
422  // set auto continue to 1
423  ret_packet.autocontinue = 1; // 1 (true), 0 (false)
424 
425  /*
426  avoid the _send() function to save memory, as it avoids
427  the stack usage of the _send() function by using the already
428  declared ret_packet above
429  */
430  ret_packet.target_system = msg->sysid;
431  ret_packet.target_component = msg->compid;
432  ret_packet.seq = packet.seq;
433  ret_packet.command = cmd.id;
434 
435  _mav_finalize_message_chan_send(chan,
436  MAVLINK_MSG_ID_MISSION_ITEM_INT,
437  (const char *)&ret_packet,
438  MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN,
439  MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN,
440  MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
441  } else {
442  // decode
443  mavlink_mission_request_t packet;
444  mavlink_msg_mission_request_decode(msg, &packet);
445 
446  if (packet.seq != 0 && // always allow HOME to be read
447  packet.seq >= mission.num_commands()) {
448  // try to educate the GCS on the actual size of the mission:
449  mavlink_msg_mission_count_send(chan,msg->sysid, msg->compid, mission.num_commands(),
450  MAV_MISSION_TYPE_MISSION);
451  goto mission_item_send_failed;
452  }
453 
454  // retrieve mission from eeprom
455  if (!mission.read_cmd_from_storage(packet.seq, cmd)) {
456  goto mission_item_send_failed;
457  }
458 
459  mavlink_mission_item_t ret_packet;
460  memset(&ret_packet, 0, sizeof(ret_packet));
461  if (!AP_Mission::mission_cmd_to_mavlink(cmd, ret_packet)) {
462  goto mission_item_send_failed;
463  }
464 
465  // set packet's current field to 1 if this is the command being executed
466  if (cmd.id == (uint16_t)mission.get_current_nav_cmd().index) {
467  ret_packet.current = 1;
468  } else {
469  ret_packet.current = 0;
470  }
471 
472  // set auto continue to 1
473  ret_packet.autocontinue = 1; // 1 (true), 0 (false)
474 
475  /*
476  avoid the _send() function to save memory, as it avoids
477  the stack usage of the _send() function by using the already
478  declared ret_packet above
479  */
480  ret_packet.target_system = msg->sysid;
481  ret_packet.target_component = msg->compid;
482  ret_packet.seq = packet.seq;
483  ret_packet.command = cmd.id;
484 
485  _mav_finalize_message_chan_send(chan,
486  MAVLINK_MSG_ID_MISSION_ITEM,
487  (const char *)&ret_packet,
488  MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN,
489  MAVLINK_MSG_ID_MISSION_ITEM_LEN,
490  MAVLINK_MSG_ID_MISSION_ITEM_CRC);
491  }
492 
493  return;
494 
495 mission_item_send_failed:
496  // send failure message
497  mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ERROR,
498  MAV_MISSION_TYPE_MISSION);
499 }
500 
501 /*
502  handle a MISSION_SET_CURRENT mavlink packet
503  */
504 void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg)
505 {
506  // decode
507  mavlink_mission_set_current_t packet;
508  mavlink_msg_mission_set_current_decode(msg, &packet);
509 
510  // set current command
511  if (mission.set_current_cmd(packet.seq)) {
512  mavlink_msg_mission_current_send(chan, packet.seq);
513  }
514 }
515 
516 /*
517  handle a MISSION_COUNT mavlink packet
518  */
519 void GCS_MAVLINK::handle_mission_count(AP_Mission &mission, mavlink_message_t *msg)
520 {
521  // decode
522  mavlink_mission_count_t packet;
523  mavlink_msg_mission_count_decode(msg, &packet);
524 
525  // start waypoint receiving
526  if (packet.count > mission.num_commands_max()) {
527  // send NAK
528  mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_NO_SPACE,
529  MAV_MISSION_TYPE_MISSION);
530  return;
531  }
532 
533  // new mission arriving, truncate mission to be the same length
534  mission.truncate(packet.count);
535 
536  // set variables to help handle the expected receiving of commands from the GCS
537  waypoint_timelast_receive = AP_HAL::millis(); // set time we last received commands to now
538  waypoint_receiving = true; // record that we expect to receive commands
539  waypoint_request_i = 0; // reset the next expected command number to zero
540  waypoint_request_last = packet.count; // record how many commands we expect to receive
541  waypoint_timelast_request = 0; // set time we last requested commands to zero
542 
543  waypoint_dest_sysid = msg->sysid; // record system id of GCS who wants to upload the mission
544  waypoint_dest_compid = msg->compid; // record component id of GCS who wants to upload the mission
545 }
546 
547 /*
548  handle a MISSION_CLEAR_ALL mavlink packet
549  */
550 void GCS_MAVLINK::handle_mission_clear_all(AP_Mission &mission, mavlink_message_t *msg)
551 {
552  // decode
553  mavlink_mission_clear_all_t packet;
554  mavlink_msg_mission_clear_all_decode(msg, &packet);
555 
556  // clear all waypoints
557  if (mission.clear()) {
558  // send ack
559  mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ACCEPTED,
560  MAV_MISSION_TYPE_MISSION);
561  }else{
562  // send nack
563  mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ERROR,
564  MAV_MISSION_TYPE_MISSION);
565  }
566 }
567 
568 /*
569  handle a MISSION_WRITE_PARTIAL_LIST mavlink packet
570  */
571 void GCS_MAVLINK::handle_mission_write_partial_list(AP_Mission &mission, mavlink_message_t *msg)
572 {
573  // decode
574  mavlink_mission_write_partial_list_t packet;
575  mavlink_msg_mission_write_partial_list_decode(msg, &packet);
576 
577  // start waypoint receiving
578  if ((unsigned)packet.start_index > mission.num_commands() ||
579  (unsigned)packet.end_index > mission.num_commands() ||
580  packet.end_index < packet.start_index) {
581  send_text(MAV_SEVERITY_WARNING,"Flight plan update rejected");
582  return;
583  }
584 
587  waypoint_receiving = true;
588  waypoint_request_i = packet.start_index;
589  waypoint_request_last= packet.end_index;
590 
591  waypoint_dest_sysid = msg->sysid; // record system id of GCS who wants to partially update the mission
592  waypoint_dest_compid = msg->compid; // record component id of GCS who wants to partially update the mission
593 }
594 
595 
596 /*
597  handle a GIMBAL_REPORT mavlink packet
598  */
599 void GCS_MAVLINK::handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const
600 {
601  mount.handle_gimbal_report(chan, msg);
602 }
603 
604 
605 void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
606 {
607  char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
608  va_list arg_list;
609  va_start(arg_list, fmt);
610  hal.util->vsnprintf((char *)text, sizeof(text), fmt, arg_list);
611  va_end(arg_list);
612  text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = 0;
613  gcs().send_statustext(severity, (1<<chan), text);
614 }
615 
616 void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio)
617 {
618  mavlink_radio_t packet;
619  mavlink_msg_radio_decode(msg, &packet);
620 
621  // record if the GCS has been receiving radio messages from
622  // the aircraft
623  if (packet.remrssi != 0) {
625  }
626 
627  // use the state of the transmit buffer in the radio to
628  // control the stream rate, giving us adaptive software
629  // flow control
630  if (packet.txbuf < 20 && stream_slowdown < 100) {
631  // we are very low on space - slow down a lot
632  stream_slowdown += 3;
633  } else if (packet.txbuf < 50 && stream_slowdown < 100) {
634  // we are a bit low on space, slow down slightly
635  stream_slowdown += 1;
636  } else if (packet.txbuf > 95 && stream_slowdown > 10) {
637  // the buffer has plenty of space, speed up a lot
638  stream_slowdown -= 2;
639  } else if (packet.txbuf > 90 && stream_slowdown != 0) {
640  // the buffer has enough space, speed up a bit
641  stream_slowdown--;
642  }
643 
644  //log rssi, noise, etc if logging Performance monitoring data
645  if (log_radio) {
646  dataflash.Log_Write_Radio(packet);
647  }
648 }
649 
650 /*
651  handle an incoming mission item
652  return true if this is the last mission item, otherwise false
653  */
654 bool GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &mission)
655 {
656  MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED;
657  struct AP_Mission::Mission_Command cmd = {};
658  bool mission_is_complete = false;
659  uint16_t seq=0;
660  uint16_t current = 0;
661 
662  if (msg->msgid == MAVLINK_MSG_ID_MISSION_ITEM) {
663  mavlink_mission_item_t packet;
664  mavlink_msg_mission_item_decode(msg, &packet);
665 
666  // convert mavlink packet to mission command
667  result = AP_Mission::mavlink_to_mission_cmd(packet, cmd);
668  if (result != MAV_MISSION_ACCEPTED) {
669  goto mission_ack;
670  }
671 
672  seq = packet.seq;
673  current = packet.current;
674  } else {
675  mavlink_mission_item_int_t packet;
676  mavlink_msg_mission_item_int_decode(msg, &packet);
677 
678  // convert mavlink packet to mission command
679  result = AP_Mission::mavlink_int_to_mission_cmd(packet, cmd);
680  if (result != MAV_MISSION_ACCEPTED) {
681  goto mission_ack;
682  }
683 
684  seq = packet.seq;
685  current = packet.current;
686  }
687 
688  if (current == 2) {
689  // current = 2 is a flag to tell us this is a "guided mode"
690  // waypoint and not for the mission
691  result = (handle_guided_request(cmd) ? MAV_MISSION_ACCEPTED
692  : MAV_MISSION_ERROR) ;
693 
694  // verify we received the command
695  goto mission_ack;
696  }
697 
698  if (current == 3) {
699  //current = 3 is a flag to tell us this is a alt change only
700  // add home alt if needed
702 
703  // verify we recevied the command
704  result = MAV_MISSION_ACCEPTED;
705  goto mission_ack;
706  }
707 
708  // Check if receiving waypoints (mission upload expected)
709  if (!waypoint_receiving) {
710  result = MAV_MISSION_ERROR;
711  goto mission_ack;
712  }
713 
714  // check if this is the requested waypoint
715  if (seq != waypoint_request_i) {
716  result = MAV_MISSION_INVALID_SEQUENCE;
717  goto mission_ack;
718  }
719 
720  // sanity check for DO_JUMP command
721  if (cmd.id == MAV_CMD_DO_JUMP) {
722  if ((cmd.content.jump.target >= mission.num_commands() && cmd.content.jump.target >= waypoint_request_last) || cmd.content.jump.target == 0) {
723  result = MAV_MISSION_ERROR;
724  goto mission_ack;
725  }
726  }
727 
728  // if command index is within the existing list, replace the command
729  if (seq < mission.num_commands()) {
730  if (mission.replace_cmd(seq,cmd)) {
731  result = MAV_MISSION_ACCEPTED;
732  }else{
733  result = MAV_MISSION_ERROR;
734  goto mission_ack;
735  }
736  // if command is at the end of command list, add the command
737  } else if (seq == mission.num_commands()) {
738  if (mission.add_cmd(cmd)) {
739  result = MAV_MISSION_ACCEPTED;
740  }else{
741  result = MAV_MISSION_ERROR;
742  goto mission_ack;
743  }
744  // if beyond the end of the command list, return an error
745  } else {
746  result = MAV_MISSION_ERROR;
747  goto mission_ack;
748  }
749 
750  // update waypoint receiving state machine
753 
755  mavlink_msg_mission_ack_send_buf(
756  msg,
757  chan,
758  msg->sysid,
759  msg->compid,
760  MAV_MISSION_ACCEPTED,
761  MAV_MISSION_TYPE_MISSION);
762 
763  send_text(MAV_SEVERITY_INFO,"Flight plan received");
764  waypoint_receiving = false;
765  mission_is_complete = true;
766  // XXX ignores waypoint radius for individual waypoints, can
767  // only set WP_RADIUS parameter
768  } else {
770  // if we have enough space, then send the next WP immediately
771  if (HAVE_PAYLOAD_SPACE(chan, MISSION_ITEM)) {
773  } else {
775  }
776  }
777  return mission_is_complete;
778 
779 mission_ack:
780  // we are rejecting the mission/waypoint
781  mavlink_msg_mission_ack_send_buf(
782  msg,
783  chan,
784  msg->sysid,
785  msg->compid,
786  result,
787  MAV_MISSION_TYPE_MISSION);
788 
789  return mission_is_complete;
790 }
791 
793 {
794  while (num_deferred_messages != 0) {
796  break;
797  }
798  next_deferred_message++;
799  if (next_deferred_message == ARRAY_SIZE(deferred_messages)) {
800  next_deferred_message = 0;
801  }
803  }
804 }
805 
807 {
809 }
810 
811 // send a message using mavlink, handling message queueing
813 {
814  uint8_t i, nextid;
815 
816  if (id == MSG_HEARTBEAT) {
817  save_signing_timestamp(false);
818  }
819 
820  // see if we can send the deferred messages, if any:
822 
823  // if there are no deferred messages, attempt to send straight away:
824  if (num_deferred_messages == 0) {
825  if (try_send_message(id)) {
826  // yay, we sent it!
827  return;
828  }
829  }
830 
831  // we failed to send the message this time around, so try to defer:
833  // the defer buffer is full, discard this attempt to send.
834  // Note that the message *may* already be in the defer buffer
835  return;
836  }
837 
838  // check if this message is deferred:
839  for (i=0, nextid = next_deferred_message; i < num_deferred_messages; i++) {
840  if (deferred_messages[nextid] == id) {
841  // it's already deferred
842  return;
843  }
844  nextid++;
845  if (nextid == ARRAY_SIZE(deferred_messages)) {
846  nextid = 0;
847  }
848  }
849 
850  // not already deferred, defer it
851  deferred_messages[nextid] = id;
852  num_deferred_messages++;
853 }
854 
855 void GCS_MAVLINK::packetReceived(const mavlink_status_t &status,
856  mavlink_message_t &msg)
857 {
858  // we exclude radio packets because we historically used this to
859  // make it possible to use the CLI over the radio
860  if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
861  mavlink_active |= (1U<<(chan-MAVLINK_COMM_0));
862  }
863  if (!(status.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) &&
864  (status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) &&
865  serialmanager_p &&
867  // if we receive any MAVLink2 packets on a connection
868  // currently sending MAVLink1 then switch to sending
869  // MAVLink2
870  mavlink_status_t *cstatus = mavlink_get_channel_status(chan);
871  if (cstatus != nullptr) {
872  cstatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
873  }
874  }
875  if (routing.check_and_forward(chan, &msg) &&
876  accept_packet(status, msg)) {
877  handleMessage(&msg);
878  }
879 }
880 
881 void
882 GCS_MAVLINK::update(uint32_t max_time_us)
883 {
884  // receive new packets
885  mavlink_message_t msg;
886  mavlink_status_t status;
887  uint32_t tstart_us = AP_HAL::micros();
888  uint32_t now_ms = AP_HAL::millis();
889 
891 
892  status.packet_rx_drop_count = 0;
893 
894  // process received bytes
895  uint16_t nbytes = comm_get_available(chan);
896  for (uint16_t i=0; i<nbytes; i++)
897  {
898  const uint8_t c = (uint8_t)_port->read();
899  const uint32_t protocol_timeout = 4000;
900 
901  if (alternative.handler &&
902  now_ms - alternative.last_mavlink_ms > protocol_timeout) {
903  /*
904  we have an alternative protocol handler installed and we
905  haven't parsed a MAVLink packet for 4 seconds. Try
906  parsing using alternative handler
907  */
908  if (alternative.handler(c, mavlink_comm_port[chan])) {
909  alternative.last_alternate_ms = now_ms;
911  }
912 
913  /*
914  we may also try parsing as MAVLink if we haven't had a
915  successful parse on the alternative protocol for 4s
916  */
917  if (now_ms - alternative.last_alternate_ms <= protocol_timeout) {
918  continue;
919  }
920  }
921 
922  bool parsed_packet = false;
923 
924  // Try to get a new message
925  if (mavlink_parse_char(chan, c, &msg, &status)) {
927  packetReceived(status, msg);
928  hal.util->perf_end(_perf_packet);
929  parsed_packet = true;
930  gcs_alternative_active[chan] = false;
931  alternative.last_mavlink_ms = now_ms;
932  }
933 
934  if (parsed_packet || i % 100 == 0) {
935  // make sure we don't spend too much time parsing mavlink messages
936  if (AP_HAL::micros() - tstart_us > max_time_us) {
937  break;
938  }
939  }
940  }
941 
942  const uint32_t tnow = AP_HAL::millis();
943 
944  // send a timesync message every 10 seconds; this is for data
945  // collection purposes
946  if (tnow - _timesync_request.last_sent_ms > _timesync_request.interval_ms) {
947  if (HAVE_PAYLOAD_SPACE(chan, TIMESYNC)) {
948  send_timesync();
949  _timesync_request.last_sent_ms = tnow;
950  }
951  }
952 
953  if (!waypoint_receiving) {
954  hal.util->perf_end(_perf_update);
955  return;
956  }
957 
958  uint32_t wp_recv_time = 1000U + (stream_slowdown*20);
959 
960  // stop waypoint receiving if timeout
962  waypoint_receiving = false;
963  } else if (waypoint_receiving &&
964  (tnow - waypoint_timelast_request) > wp_recv_time) {
967  }
968 
969  hal.util->perf_end(_perf_update);
970 }
971 
972 
973 /*
974  send the SYSTEM_TIME message
975  */
977 {
978  mavlink_msg_system_time_send(
979  chan,
980  AP::gps().time_epoch_usec(),
981  AP_HAL::millis());
982 }
983 
984 
985 /*
986  send RC_CHANNELS messages
987  */
989 {
990  AP_RSSI *rssi = AP::rssi();
991  uint8_t receiver_rssi = 0;
992  if (rssi != nullptr) {
993  receiver_rssi = rssi->read_receiver_rssi_uint8();
994  }
995 
996  uint32_t now = AP_HAL::millis();
997  mavlink_status_t *status = mavlink_get_channel_status(chan);
998 
999  uint16_t values[18];
1000  RC_Channels::get_radio_in(values, 18);
1001 
1002  if (status && (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
1003  // for mavlink1 send RC_CHANNELS_RAW, for compatibility with OSD implementations
1004  mavlink_msg_rc_channels_raw_send(
1005  chan,
1006  now,
1007  0,
1008  values[0],
1009  values[1],
1010  values[2],
1011  values[3],
1012  values[4],
1013  values[5],
1014  values[6],
1015  values[7],
1016  receiver_rssi);
1017  }
1018  if (!HAVE_PAYLOAD_SPACE(chan, RC_CHANNELS)) {
1019  // can't fit RC_CHANNELS
1020  return;
1021  }
1022  mavlink_msg_rc_channels_send(
1023  chan,
1024  now,
1026  values[0],
1027  values[1],
1028  values[2],
1029  values[3],
1030  values[4],
1031  values[5],
1032  values[6],
1033  values[7],
1034  values[8],
1035  values[9],
1036  values[10],
1037  values[11],
1038  values[12],
1039  values[13],
1040  values[14],
1041  values[15],
1042  values[16],
1043  values[17],
1044  receiver_rssi);
1045 }
1046 
1048 {
1049  const AP_InertialSensor &ins = AP::ins();
1050  const Compass &compass = AP::compass();
1051 
1052  const Vector3f &accel = ins.get_accel(0);
1053  const Vector3f &gyro = ins.get_gyro(0);
1054  Vector3f mag;
1055  if (compass.get_count() >= 1) {
1056  mag = compass.get_field(0);
1057  } else {
1058  mag.zero();
1059  }
1060 
1061  mavlink_msg_raw_imu_send(
1062  chan,
1063  AP_HAL::micros(),
1064  accel.x * 1000.0f / GRAVITY_MSS,
1065  accel.y * 1000.0f / GRAVITY_MSS,
1066  accel.z * 1000.0f / GRAVITY_MSS,
1067  gyro.x * 1000.0f,
1068  gyro.y * 1000.0f,
1069  gyro.z * 1000.0f,
1070  mag.x,
1071  mag.y,
1072  mag.z);
1073 
1074  if (ins.get_gyro_count() <= 1 &&
1075  ins.get_accel_count() <= 1 &&
1076  compass.get_count() <= 1) {
1077  return;
1078  }
1079  if (!HAVE_PAYLOAD_SPACE(chan, SCALED_IMU2)) {
1080  return;
1081  }
1082  const Vector3f &accel2 = ins.get_accel(1);
1083  const Vector3f &gyro2 = ins.get_gyro(1);
1084  if (compass.get_count() >= 2) {
1085  mag = compass.get_field(1);
1086  } else {
1087  mag.zero();
1088  }
1089  mavlink_msg_scaled_imu2_send(
1090  chan,
1091  AP_HAL::millis(),
1092  accel2.x * 1000.0f / GRAVITY_MSS,
1093  accel2.y * 1000.0f / GRAVITY_MSS,
1094  accel2.z * 1000.0f / GRAVITY_MSS,
1095  gyro2.x * 1000.0f,
1096  gyro2.y * 1000.0f,
1097  gyro2.z * 1000.0f,
1098  mag.x,
1099  mag.y,
1100  mag.z);
1101 
1102  if (ins.get_gyro_count() <= 2 &&
1103  ins.get_accel_count() <= 2 &&
1104  compass.get_count() <= 2) {
1105  return;
1106  }
1107  if (!HAVE_PAYLOAD_SPACE(chan, SCALED_IMU3)) {
1108  return;
1109  }
1110  const Vector3f &accel3 = ins.get_accel(2);
1111  const Vector3f &gyro3 = ins.get_gyro(2);
1112  if (compass.get_count() >= 3) {
1113  mag = compass.get_field(2);
1114  } else {
1115  mag.zero();
1116  }
1117  mavlink_msg_scaled_imu3_send(
1118  chan,
1119  AP_HAL::millis(),
1120  accel3.x * 1000.0f / GRAVITY_MSS,
1121  accel3.y * 1000.0f / GRAVITY_MSS,
1122  accel3.z * 1000.0f / GRAVITY_MSS,
1123  gyro3.x * 1000.0f,
1124  gyro3.y * 1000.0f,
1125  gyro3.z * 1000.0f,
1126  mag.x,
1127  mag.y,
1128  mag.z);
1129 }
1130 
1131 // sub overrides this to send on-board temperature
1133 {
1134  const AP_Baro &barometer = AP::baro();
1135 
1136  if (barometer.num_instances() < 3) {
1137  return;
1138  }
1139  if (!HAVE_PAYLOAD_SPACE(chan, SCALED_PRESSURE3)) {
1140  return;
1141  }
1142 
1143  const float pressure = barometer.get_pressure(2);
1144  mavlink_msg_scaled_pressure3_send(
1145  chan,
1146  AP_HAL::millis(),
1147  pressure*0.01f, // hectopascal
1148  (pressure - barometer.get_ground_pressure(2))*0.01f, // hectopascal
1149  barometer.get_temperature(2)*100); // 0.01 degrees C
1150 }
1151 
1153 {
1154  uint32_t now = AP_HAL::millis();
1155  const AP_Baro &barometer = AP::baro();
1156  float pressure = barometer.get_pressure(0);
1157  float diff_pressure = 0; // pascal
1158 
1160  if (airspeed != nullptr) {
1161  diff_pressure = airspeed->get_differential_pressure();
1162  }
1163 
1164  mavlink_msg_scaled_pressure_send(
1165  chan,
1166  now,
1167  pressure*0.01f, // hectopascal
1168  diff_pressure*0.01f, // hectopascal
1169  barometer.get_temperature(0)*100); // 0.01 degrees C
1170 
1171  if (barometer.num_instances() > 1 &&
1172  HAVE_PAYLOAD_SPACE(chan, SCALED_PRESSURE2)) {
1173  pressure = barometer.get_pressure(1);
1174  mavlink_msg_scaled_pressure2_send(
1175  chan,
1176  now,
1177  pressure*0.01f, // hectopascal
1178  (pressure - barometer.get_ground_pressure(1))*0.01f, // hectopascal
1179  barometer.get_temperature(1)*100); // 0.01 degrees C
1180  }
1181 
1183 }
1184 
1186 {
1187  const AP_InertialSensor &ins = AP::ins();
1188  const Compass &compass = AP::compass();
1189 
1190  // run this message at a much lower rate - otherwise it
1191  // pointlessly wastes quite a lot of bandwidth
1192  static uint8_t counter;
1193  if (counter++ < 10) {
1194  return;
1195  }
1196  counter = 0;
1197 
1198  const Vector3f &mag_offsets = compass.get_offsets(0);
1199  const Vector3f &accel_offsets = ins.get_accel_offsets(0);
1200  const Vector3f &gyro_offsets = ins.get_gyro_offsets(0);
1201 
1202  const AP_Baro &barometer = AP::baro();
1203 
1204  mavlink_msg_sensor_offsets_send(chan,
1205  mag_offsets.x,
1206  mag_offsets.y,
1207  mag_offsets.z,
1208  compass.get_declination(),
1209  barometer.get_pressure(),
1210  barometer.get_temperature()*100,
1211  gyro_offsets.x,
1212  gyro_offsets.y,
1213  gyro_offsets.z,
1214  accel_offsets.x,
1215  accel_offsets.y,
1216  accel_offsets.z);
1217 }
1218 
1220 {
1221  const AP_AHRS &ahrs = AP::ahrs();
1222  const Vector3f &omega_I = ahrs.get_gyro_drift();
1223  mavlink_msg_ahrs_send(
1224  chan,
1225  omega_I.x,
1226  omega_I.y,
1227  omega_I.z,
1228  0,
1229  0,
1230  ahrs.get_error_rp(),
1231  ahrs.get_error_yaw());
1232 }
1233 
1234 /*
1235  send a statustext text string to specific MAVLink bitmask
1236 */
1237 void GCS::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
1238 {
1239  if (dataflash_p != nullptr) {
1240  dataflash_p->Log_Write_Message(text);
1241  }
1242 
1243  // add statustext message to FrSky lib queue
1244  if (frsky_telemetry_p != NULL) {
1245  frsky_telemetry_p->queue_message(severity, text);
1246  }
1247 
1248  // filter destination ports to only allow active ports.
1249  statustext_t statustext{};
1251  if (!statustext.bitmask) {
1252  // nowhere to send
1253  return;
1254  }
1255 
1256  statustext.msg.severity = severity;
1257  strncpy(statustext.msg.text, text, sizeof(statustext.msg.text));
1258 
1259  // The force push will ensure comm links do not block other comm links forever if they fail.
1260  // If we push to a full buffer then we overwrite the oldest entry, effectively removing the
1261  // block but not until the buffer fills up.
1262  _statustext_queue.push_force(statustext);
1263 
1264  // try and send immediately if possible
1265  service_statustext();
1266 
1267  AP_Notify *notify = AP_Notify::instance();
1268  if (notify) {
1269  notify->send_text(text);
1270  }
1271 }
1272 
1273 /*
1274  send a statustext message to specific MAVLink connections in a bitmask
1275  */
1277 {
1278  // create bitmask of what mavlink ports we should send this text to.
1279  // note, if sending to all ports, we only need to store the bitmask for each and the string only once.
1280  // once we send over a link, clear the port but other busy ports bit may stay allowing for faster links
1281  // to clear the bit and send quickly but slower links to still store the string. Regardless of mixed
1282  // bitrates of ports, a maximum of _status_capacity strings can be buffered. Downside
1283  // is if you have a super slow link mixed with a faster port, if there are _status_capacity
1284  // strings in the slow queue then the next item can not be queued for the faster link
1285 
1286  if (_statustext_queue.empty()) {
1287  // nothing to do
1288  return;
1289  }
1290 
1291  for (uint8_t idx=0; idx<_status_capacity; ) {
1292  statustext_t *statustext = _statustext_queue[idx];
1293  if (statustext == nullptr) {
1294  break;
1295  }
1296 
1297  // try and send to all active mavlink ports listed in the statustext.bitmask
1298  for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
1299  uint8_t chan_bit = (1U<<i);
1300  // logical AND (&) to mask them together
1301  if (statustext->bitmask & chan_bit) {
1302  // something is queued on a port and that's the port index we're looped at
1303  mavlink_channel_t chan_index = (mavlink_channel_t)(MAVLINK_COMM_0+i);
1304  if (HAVE_PAYLOAD_SPACE(chan_index, STATUSTEXT)) {
1305  // we have space so send then clear that channel bit on the mask
1306  mavlink_msg_statustext_send(chan_index, statustext->msg.severity, statustext->msg.text);
1307  statustext->bitmask &= ~chan_bit;
1308  }
1309  }
1310  }
1311 
1312  if (statustext->bitmask == 0) {
1313  _statustext_queue.remove(idx);
1314  } else {
1315  // move to next index
1316  idx++;
1317  }
1318  }
1319 }
1320 
1322 {
1323  for (uint8_t i=0; i<num_gcs(); i++) {
1324  if (chan(i).initialised) {
1325  chan(i).send_message(id);
1326  }
1327  }
1328 }
1329 
1331 {
1332  for (uint8_t i=0; i<num_gcs(); i++) {
1333  if (chan(i).initialised) {
1334  chan(i).retry_deferred();
1335  }
1336  }
1337  service_statustext();
1338 }
1339 
1341 {
1342  for (uint8_t i=0; i<num_gcs(); i++) {
1343  if (chan(i).initialised) {
1344  chan(i).data_stream_send();
1345  }
1346  }
1347 }
1348 
1349 void GCS::update(void)
1350 {
1351  for (uint8_t i=0; i<num_gcs(); i++) {
1352  if (chan(i).initialised) {
1353  chan(i).update();
1354  }
1355  }
1356 }
1357 
1358 void GCS::send_mission_item_reached_message(uint16_t mission_index)
1359 {
1360  for (uint8_t i=0; i<num_gcs(); i++) {
1361  if (chan(i).initialised) {
1362  chan(i).mission_item_reached_index = mission_index;
1363  chan(i).send_message(MSG_MISSION_ITEM_REACHED);
1364  }
1365  }
1366 }
1367 
1369 {
1370  for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
1371  chan(i).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
1372  }
1373 }
1374 
1375 // report battery2 state
1377 {
1378  const AP_BattMonitor &battery = AP::battery();
1379 
1380  if (battery.num_instances() > 1) {
1381  int16_t current;
1382  if (battery.has_current(1)) {
1383  current = battery.current_amps(1) * 100; // 10*mA
1384  } else {
1385  current = -1;
1386  }
1387  mavlink_msg_battery2_send(chan, battery.voltage(1)*1000, current);
1388  }
1389 }
1390 
1391 /*
1392  handle a SET_MODE MAVLink message
1393  */
1394 void GCS_MAVLINK::handle_set_mode(mavlink_message_t* msg)
1395 {
1396  mavlink_set_mode_t packet;
1397  mavlink_msg_set_mode_decode(msg, &packet);
1398 
1399  const MAV_MODE _base_mode = (MAV_MODE)packet.base_mode;
1400  const uint32_t _custom_mode = packet.custom_mode;
1401 
1402  const MAV_RESULT result = _set_mode_common(_base_mode, _custom_mode);
1403 
1404  // send ACK or NAK
1405  mavlink_msg_command_ack_send_buf(msg, chan, MAVLINK_MSG_ID_SET_MODE, result);
1406 }
1407 
1408 /*
1409  code common to both SET_MODE mavlink message and command long set_mode msg
1410 */
1411 MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32_t _custom_mode)
1412 {
1413  MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
1414  // only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes
1415  if (_base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
1416  if (set_mode(_custom_mode)) {
1417  result = MAV_RESULT_ACCEPTED;
1418  }
1419  } else if (_base_mode == (MAV_MODE)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
1420  // set the safety switch position. Must be in a command by itself
1421  if (_custom_mode == 0) {
1422  // turn safety off (pwm outputs flow to the motors)
1423  hal.rcout->force_safety_off();
1424  result = MAV_RESULT_ACCEPTED;
1425  } else if (_custom_mode == 1) {
1426  // turn safety on (no pwm outputs to the motors)
1427  if (hal.rcout->force_safety_on()) {
1428  result = MAV_RESULT_ACCEPTED;
1429  }
1430  }
1431  }
1432 
1433  return result;
1434 }
1435 
1436 #if AP_AHRS_NAVEKF_AVAILABLE
1437 /*
1438  send OPTICAL_FLOW message
1439  */
1440 void GCS_MAVLINK::send_opticalflow(const OpticalFlow &optflow)
1441 {
1442  // exit immediately if no optical flow sensor or not healthy
1443  if (!optflow.healthy()) {
1444  return;
1445  }
1446 
1447  // get rates from sensor
1448  const Vector2f &flowRate = optflow.flowRate();
1449  const Vector2f &bodyRate = optflow.bodyRate();
1450 
1451  const AP_AHRS &ahrs = AP::ahrs();
1452  float hagl = 0;
1453  if (ahrs.have_inertial_nav()) {
1454  if (!ahrs.get_hagl(hagl)) {
1455  return;
1456  }
1457  }
1458 
1459  // populate and send message
1460  mavlink_msg_optical_flow_send(
1461  chan,
1462  AP_HAL::millis(),
1463  0, // sensor id is zero
1464  flowRate.x,
1465  flowRate.y,
1466  bodyRate.x,
1467  bodyRate.y,
1468  optflow.quality(),
1469  hagl, // ground distance (in meters) set to zero
1470  flowRate.x,
1471  flowRate.y);
1472 }
1473 #endif
1474 
1475 /*
1476  send AUTOPILOT_VERSION packet
1477  */
1479 {
1480  uint32_t flight_sw_version;
1481  uint32_t middleware_sw_version = 0;
1482  uint32_t os_sw_version = 0;
1483  uint32_t board_version = 0;
1484  char flight_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN]{};
1485  char middleware_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN]{};
1486  char os_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN]{};
1487  uint16_t vendor_id = 0;
1488  uint16_t product_id = 0;
1489  uint64_t uid = 0;
1490  uint8_t uid2[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN] = {0};
1491  const AP_FWVersion &version = get_fwver();
1492 
1493  flight_sw_version = version.major << (8 * 3) | \
1494  version.minor << (8 * 2) | \
1495  version.patch << (8 * 1) | \
1496  (uint32_t)(version.fw_type) << (8 * 0);
1497 
1498  if (version.fw_hash_str) {
1499  strncpy(flight_custom_version, version.fw_hash_str, sizeof(flight_custom_version) - 1);
1500  flight_custom_version[sizeof(flight_custom_version) - 1] = '\0';
1501  }
1502 
1503  if (version.middleware_hash_str) {
1504  strncpy(middleware_custom_version, version.middleware_hash_str, sizeof(middleware_custom_version) - 1);
1505  middleware_custom_version[sizeof(middleware_custom_version) - 1] = '\0';
1506  }
1507 
1508  if (version.os_hash_str) {
1509  strncpy(os_custom_version, version.os_hash_str, sizeof(os_custom_version) - 1);
1510  os_custom_version[sizeof(os_custom_version) - 1] = '\0';
1511  }
1512 
1513  mavlink_msg_autopilot_version_send(
1514  chan,
1515  hal.util->get_capabilities(),
1516  flight_sw_version,
1517  middleware_sw_version,
1518  os_sw_version,
1519  board_version,
1520  (uint8_t *)flight_custom_version,
1521  (uint8_t *)middleware_custom_version,
1522  (uint8_t *)os_custom_version,
1523  vendor_id,
1524  product_id,
1525  uid,
1526  uid2
1527  );
1528 }
1529 
1530 
1531 /*
1532  send LOCAL_POSITION_NED message
1533  */
1535 {
1536  const AP_AHRS &ahrs = AP::ahrs();
1537 
1538  Vector3f local_position, velocity;
1539  if (!ahrs.get_relative_position_NED_home(local_position) ||
1540  !ahrs.get_velocity_NED(velocity)) {
1541  // we don't know the position and velocity
1542  return;
1543  }
1544 
1545  mavlink_msg_local_position_ned_send(
1546  chan,
1547  AP_HAL::millis(),
1548  local_position.x,
1549  local_position.y,
1550  local_position.z,
1551  velocity.x,
1552  velocity.y,
1553  velocity.z);
1554 }
1555 
1556 /*
1557  send VIBRATION message
1558  */
1560 {
1561  const AP_InertialSensor &ins = AP::ins();
1562 
1563  Vector3f vibration = ins.get_vibration_levels();
1564 
1565  mavlink_msg_vibration_send(
1566  chan,
1567  AP_HAL::micros64(),
1568  vibration.x,
1569  vibration.y,
1570  vibration.z,
1571  ins.get_accel_clip_count(0),
1572  ins.get_accel_clip_count(1),
1573  ins.get_accel_clip_count(2));
1574 }
1575 
1576 void GCS_MAVLINK::send_named_float(const char *name, float value) const
1577 {
1578  char float_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN+1] {};
1579  strncpy(float_name, name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
1580  mavlink_msg_named_value_float_send(chan, AP_HAL::millis(), float_name, value);
1581 }
1582 
1584 {
1585  if (!HAVE_PAYLOAD_SPACE(chan, HOME_POSITION)) {
1586  return;
1587  }
1588  if (!AP::ahrs().home_is_set()) {
1589  return;
1590  }
1591 
1592  Location home = AP::ahrs().get_home();
1593 
1594  const float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};
1595  mavlink_msg_home_position_send(
1596  chan,
1597  home.lat,
1598  home.lng,
1599  home.alt * 10,
1600  0.0f, 0.0f, 0.0f,
1601  q,
1602  0.0f, 0.0f, 0.0f,
1603  AP_HAL::micros64());
1604 }
1605 
1607 {
1608  if (!HAVE_PAYLOAD_SPACE(chan, GPS_GLOBAL_ORIGIN)) {
1609  return;
1610  }
1612  if (!AP::ahrs().get_origin(ekf_origin)) {
1613  return;
1614  }
1615  mavlink_msg_gps_global_origin_send(
1616  chan,
1617  ekf_origin.lat,
1618  ekf_origin.lng,
1619  ekf_origin.alt * 10,
1620  AP_HAL::micros64());
1621 }
1622 
1623 /*
1624  Send MAVLink heartbeat
1625  */
1627 {
1628  mavlink_msg_heartbeat_send(
1629  chan,
1630  frame_type(),
1631  MAV_AUTOPILOT_ARDUPILOTMEGA,
1632  base_mode(),
1633  custom_mode(),
1634  system_status());
1635 }
1636 
1638 {
1639  // send at a much lower rate while handling waypoints and
1640  // parameter sends
1641  if ((stream_num != STREAM_PARAMS) &&
1642  (waypoint_receiving || _queued_parameter != nullptr)) {
1643  return 0.25f;
1644  }
1645 
1646  return 1.0f;
1647 }
1648 
1649 // are we still delaying telemetry to try to avoid Xbee bricking?
1651 {
1652  uint32_t tnow = AP_HAL::millis() >> 10;
1653  if (tnow > telem_delay()) {
1654  return false;
1655  }
1656  if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
1657  // this is USB telemetry, so won't be an Xbee
1658  return false;
1659  }
1660  // we're either on the 2nd UART, or no USB cable is connected
1661  // we need to delay telemetry by the TELEM_DELAY time
1662  return true;
1663 }
1664 
1665 
1666 /*
1667  send SERVO_OUTPUT_RAW
1668  */
1670 {
1671  uint16_t values[16] {};
1672  if (in_hil_mode()) {
1673  for (uint8_t i=0; i<16; i++) {
1674  values[i] = SRV_Channels::srv_channel(i)->get_output_pwm();
1675  }
1676  } else {
1677  hal.rcout->read(values, 16);
1678  }
1679  for (uint8_t i=0; i<16; i++) {
1680  if (values[i] == 65535) {
1681  values[i] = 0;
1682  }
1683  }
1684  mavlink_msg_servo_output_raw_send(
1685  chan,
1686  AP_HAL::micros(),
1687  0, // port
1688  values[0], values[1], values[2], values[3],
1689  values[4], values[5], values[6], values[7],
1690  values[8], values[9], values[10], values[11],
1691  values[12], values[13], values[14], values[15]);
1692 }
1693 
1694 
1695 void GCS_MAVLINK::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour)
1696 {
1697  for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
1698  if ((1U<<i) & mavlink_active) {
1699  mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
1700  if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_COLLISION) {
1701  mavlink_msg_collision_send(
1702  chan,
1703  MAV_COLLISION_SRC_ADSB,
1704  threat.src_id,
1705  behaviour,
1706  threat.threat_level,
1707  threat.time_to_closest_approach,
1708  threat.closest_approach_z,
1709  threat.closest_approach_xy
1710  );
1711  }
1712  }
1713  }
1714 }
1715 
1717 {
1718  if (HAVE_PAYLOAD_SPACE(chan, COMMAND_LONG)) {
1719  mavlink_msg_command_long_send(
1720  chan,
1721  0,
1722  0,
1723  MAV_CMD_ACCELCAL_VEHICLE_POS,
1724  0,
1725  (float) position,
1726  0, 0, 0, 0, 0, 0);
1727  }
1728 }
1729 
1730 
1732 {
1734  if (airspeed != nullptr && airspeed->healthy()) {
1735  return airspeed->get_airspeed();
1736  }
1737  // because most vehicles don't have airspeed sensors, we return a
1738  // different sort of speed estimate in the relevant field for
1739  // comparison's sake.
1740  return AP::gps().ground_speed();
1741 }
1742 
1744 {
1745  return -vfr_hud_velned.z;
1746 }
1747 
1749 {
1750  AP_AHRS &ahrs = AP::ahrs();
1751 
1752  // return values ignored; we send stale data
1755 
1756  float alt;
1757  if (vfr_hud_make_alt_relative()) {
1758  ahrs.get_relative_position_D_home(alt);
1759  alt = -alt;
1760  } else {
1761  alt = global_position_current_loc.alt / 100.0f;
1762  }
1763  mavlink_msg_vfr_hud_send(
1764  chan,
1765  vfr_hud_airspeed(),
1766  ahrs.groundspeed(),
1767  (ahrs.yaw_sensor / 100) % 360,
1768  vfr_hud_throttle(),
1769  alt,
1770  vfr_hud_climbrate());
1771 }
1772 
1773 /*
1774  handle a MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command
1775 
1776  Optionally disable PX4IO overrides. This is done for quadplanes to
1777  prevent the mixer running while rebooting which can start the VTOL
1778  motors. That can be dangerous when a preflight reboot is done with
1779  the pilot close to the aircraft and can also damage the aircraft
1780  */
1781 MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides)
1782 {
1783  if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
1784  if (disable_overrides) {
1785 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
1786  // disable overrides while rebooting
1787  int px4io_fd = open("/dev/px4io", 0);
1788  if (px4io_fd >= 0) {
1789  // disable OVERRIDES so we don't run the mixer while
1790  // rebooting
1791  if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_OK, 0) != 0) {
1792  hal.console->printf("SET_OVERRIDE_OK failed\n");
1793  }
1794  if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 0) != 0) {
1795  hal.console->printf("SET_OVERRIDE_IMMEDIATE failed\n");
1796  }
1797  close(px4io_fd);
1798  }
1799 #endif
1800  }
1801 
1802  // force safety on
1803  hal.rcout->force_safety_on();
1804  hal.rcout->force_safety_no_wait();
1805  hal.scheduler->delay(200);
1806 
1807  // when packet.param1 == 3 we reboot to hold in bootloader
1808  bool hold_in_bootloader = is_equal(packet.param1,3.0f);
1809  hal.scheduler->reboot(hold_in_bootloader);
1810  return MAV_RESULT_ACCEPTED;
1811  }
1812  return MAV_RESULT_UNSUPPORTED;
1813 }
1814 
1815 /*
1816  handle a flight termination request
1817  */
1818 MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_long_t &packet)
1819 {
1821  if (failsafe == nullptr) {
1822  return MAV_RESULT_UNSUPPORTED;
1823  }
1824 
1825  bool should_terminate = packet.param1 > 0.5f;
1826 
1827  if (failsafe->gcs_terminate(should_terminate, "GCS request")) {
1828  return MAV_RESULT_ACCEPTED;
1829  }
1830  return MAV_RESULT_FAILED;
1831 }
1832 
1833 /*
1834  handle a R/C bind request (for spektrum)
1835  */
1836 MAV_RESULT GCS_MAVLINK::handle_rc_bind(const mavlink_command_long_t &packet)
1837 {
1838  // initiate bind procedure. We accept the DSM type from either
1839  // param1 or param2 due to a past mixup with what parameter is the
1840  // right one
1841  if (!RC_Channels::receiver_bind(packet.param2>0?packet.param2:packet.param1)) {
1842  return MAV_RESULT_FAILED;
1843  }
1844  return MAV_RESULT_ACCEPTED;
1845 }
1846 
1848 {
1849  uint64_t ret = _port->receive_time_constraint_us(PAYLOAD_SIZE(chan, TIMESYNC));
1850  if (ret == 0) {
1851  ret = AP_HAL::micros64();
1852  }
1853  return ret*1000LL;
1854 }
1855 
1857 {
1858  // we add in our own system id try to ensure we only consider
1859  // responses to our own timesync request messages
1860  return AP_HAL::micros64()*1000LL + mavlink_system.sysid;
1861 }
1862 
1863 /*
1864  return a timesync request
1865  Sends back ts1 as received, and tc1 is the local timestamp in usec
1866  */
1867 void GCS_MAVLINK::handle_timesync(mavlink_message_t *msg)
1868 {
1869  // decode incoming timesync message
1870  mavlink_timesync_t tsync;
1871  mavlink_msg_timesync_decode(msg, &tsync);
1872 
1873  if (tsync.tc1 != 0) {
1874  // this is a response to a timesync request
1875  if (tsync.ts1 != _timesync_request.sent_ts1) {
1876  // we didn't actually send the request.... or it's a
1877  // response to an ancient request...
1878  return;
1879  }
1880  const uint64_t round_trip_time_us = (timesync_receive_timestamp_ns() - _timesync_request.sent_ts1)*0.001f;
1881 #if 0
1882  gcs().send_text(MAV_SEVERITY_INFO,
1883  "timesync response sysid=%u (latency=%fms)",
1884  msg->sysid,
1885  round_trip_time_us*0.001f);
1886 #endif
1888  if (df != nullptr) {
1890  "TSYN",
1891  "TimeUS,SysID,RTT",
1892  "s-s",
1893  "F-F",
1894  "QBQ",
1895  AP_HAL::micros64(),
1896  msg->sysid,
1897  round_trip_time_us
1898  );
1899  }
1900  return;
1901  }
1902 
1903  // create new timesync struct with tc1 field as system time in
1904  // nanoseconds. The client timestamp is as close as possible to
1905  // the time we received the TIMESYNC message.
1906  mavlink_timesync_t rsync;
1907  rsync.tc1 = timesync_receive_timestamp_ns();
1908  rsync.ts1 = tsync.ts1;
1909 
1910  // respond with a timesync message
1911  mavlink_msg_timesync_send(
1912  chan,
1913  rsync.tc1,
1914  rsync.ts1
1915  );
1916 }
1917 
1918 /*
1919  * broadcast a timesync message. We may get multiple responses to this request.
1920  */
1922 {
1924  mavlink_msg_timesync_send(
1925  chan,
1926  0,
1927  _timesync_request.sent_ts1
1928  );
1929 }
1930 
1931 void GCS_MAVLINK::handle_statustext(mavlink_message_t *msg)
1932 {
1934  if (df == nullptr) {
1935  return;
1936  }
1937 
1938  mavlink_statustext_t packet;
1939  mavlink_msg_statustext_decode(msg, &packet);
1940  const uint8_t max_prefix_len = 20;
1941  const uint8_t text_len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1+max_prefix_len;
1942  char text[text_len] = { 'G','C','S',':'};
1943  uint8_t offset = strlen(text);
1944 
1945  if (msg->sysid != sysid_my_gcs()) {
1946  offset = hal.util->snprintf(text,
1947  max_prefix_len,
1948  "SRC=%u/%u:",
1949  msg->sysid,
1950  msg->compid);
1951  }
1952 
1953  memcpy(&text[offset], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
1954 
1955  df->Log_Write_Message(text);
1956 }
1957 
1958 
1959 void GCS_MAVLINK::handle_common_gps_message(mavlink_message_t *msg)
1960 {
1961  AP::gps().handle_msg(msg);
1962 }
1963 
1964 
1965 void GCS_MAVLINK::handle_common_camera_message(const mavlink_message_t *msg)
1966 {
1967  AP_Camera *camera = get_camera();
1968  if (camera == nullptr) {
1969  return;
1970  }
1971 
1972  switch (msg->msgid) {
1973  case MAVLINK_MSG_ID_DIGICAM_CONFIGURE: // MAV ID: 202
1974  //deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
1975  break;
1976  case MAVLINK_MSG_ID_DIGICAM_CONTROL:
1977  //deprecated. Use MAV_CMD_DO_DIGICAM_CONTROL
1978  camera->control_msg(msg);
1979  break;
1980  default:
1981  break;
1982  }
1983 }
1984 MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &packet)
1985 {
1986  AP_Camera *camera = get_camera();
1987  if (camera == nullptr) {
1988  return MAV_RESULT_UNSUPPORTED;
1989  }
1990 
1991  MAV_RESULT result = MAV_RESULT_FAILED;
1992  switch (packet.command) {
1993  case MAV_CMD_DO_DIGICAM_CONFIGURE:
1994  camera->configure(packet.param1,
1995  packet.param2,
1996  packet.param3,
1997  packet.param4,
1998  packet.param5,
1999  packet.param6,
2000  packet.param7);
2001  result = MAV_RESULT_ACCEPTED;
2002  break;
2003  case MAV_CMD_DO_DIGICAM_CONTROL:
2004  camera->control(packet.param1,
2005  packet.param2,
2006  packet.param3,
2007  packet.param4,
2008  packet.param5,
2009  packet.param6);
2010  result = MAV_RESULT_ACCEPTED;
2011  break;
2012  case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
2013  camera->set_trigger_distance(packet.param1);
2014  result = MAV_RESULT_ACCEPTED;
2015  break;
2016  default:
2017  result = MAV_RESULT_UNSUPPORTED;
2018  break;
2019  }
2020  return result;
2021 }
2022 
2023 // sets ekf_origin if it has not been set.
2024 // should only be used when there is no GPS to provide an absolute position
2026 {
2027  // check location is valid
2028  if (!check_latlng(loc)) {
2029  return;
2030  }
2031 
2032  AP_AHRS &ahrs = AP::ahrs();
2033 
2034  // check if EKF origin has already been set
2036  if (ahrs.get_origin(ekf_origin)) {
2037  return;
2038  }
2039 
2040  if (!ahrs.set_origin(loc)) {
2041  return;
2042  }
2043 
2044  // log ahrs home and ekf origin dataflash
2046 
2047  // send ekf origin to GCS
2048  send_ekf_origin();
2049 }
2050 
2051 void GCS_MAVLINK::handle_set_gps_global_origin(const mavlink_message_t *msg)
2052 {
2053  mavlink_set_gps_global_origin_t packet;
2054  mavlink_msg_set_gps_global_origin_decode(msg, &packet);
2055 
2056  // sanity check location
2057  if (!check_latlng(packet.latitude, packet.longitude)) {
2058  // silently drop the request
2059  return;
2060  }
2061 
2062  Location ekf_origin {};
2063  ekf_origin.lat = packet.latitude;
2064  ekf_origin.lng = packet.longitude;
2065  ekf_origin.alt = packet.altitude / 10;
2067 }
2068 
2069 /*
2070  handle a DATA96 message
2071  */
2072 void GCS_MAVLINK::handle_data_packet(mavlink_message_t *msg)
2073 {
2074 #if HAL_RCINPUT_WITH_AP_RADIO
2075  mavlink_data96_t m;
2076  mavlink_msg_data96_decode(msg, &m);
2077  switch (m.type) {
2078  case 42:
2079  case 43: {
2080  // pass to AP_Radio (for firmware upload and playing test tunes)
2081  AP_Radio *radio = AP_Radio::instance();
2082  if (radio != nullptr) {
2083  radio->handle_data_packet(chan, m);
2084  }
2085  break;
2086  }
2087  default:
2088  // unknown
2089  break;
2090  }
2091 #endif
2092 }
2093 
2094 void GCS_MAVLINK::handle_vision_position_delta(mavlink_message_t *msg)
2095 {
2096  AP_VisualOdom *visual_odom = get_visual_odom();
2097  if (visual_odom == nullptr) {
2098  return;
2099  }
2100  visual_odom->handle_msg(msg);
2101 }
2102 
2104 {
2105  mavlink_vision_position_estimate_t m;
2106  mavlink_msg_vision_position_estimate_decode(msg, &m);
2107 
2108  handle_common_vision_position_estimate_data(m.usec, m.x, m.y, m.z, m.roll, m.pitch, m.yaw,
2109  PAYLOAD_SIZE(chan, VISION_POSITION_ESTIMATE));
2110 }
2111 
2113 {
2114  mavlink_global_vision_position_estimate_t m;
2115  mavlink_msg_global_vision_position_estimate_decode(msg, &m);
2116 
2117  handle_common_vision_position_estimate_data(m.usec, m.x, m.y, m.z, m.roll, m.pitch, m.yaw,
2118  PAYLOAD_SIZE(chan, GLOBAL_VISION_POSITION_ESTIMATE));
2119 }
2120 
2122 {
2123  mavlink_vicon_position_estimate_t m;
2124  mavlink_msg_vicon_position_estimate_decode(msg, &m);
2125 
2126  handle_common_vision_position_estimate_data(m.usec, m.x, m.y, m.z, m.roll, m.pitch, m.yaw,
2127  PAYLOAD_SIZE(chan, VICON_POSITION_ESTIMATE));
2128 }
2129 
2130 // there are several messages which all have identical fields in them.
2131 // This function provides common handling for the data contained in
2132 // these packets
2134  const float x,
2135  const float y,
2136  const float z,
2137  const float roll,
2138  const float pitch,
2139  const float yaw,
2140  const uint16_t payload_size)
2141 {
2142  // correct offboard timestamp to be in local ms since boot
2143  uint32_t timestamp_ms = correct_offboard_timestamp_usec_to_ms(usec, payload_size);
2144 
2145  // sensor assumed to be at 0,0,0 body-frame; need parameters for this?
2146  // or a new message
2147  const Vector3f sensor_offset = {};
2148  const Vector3f pos = {
2149  x,
2150  y,
2151  z
2152  };
2153  Quaternion attitude;
2154  attitude.from_euler(roll, pitch, yaw); // from_vector312?
2155  const float posErr = 0; // parameter required?
2156  const float angErr = 0; // parameter required?
2157  const uint32_t reset_timestamp_ms = 0; // no data available
2158 
2159  AP::ahrs().writeExtNavData(sensor_offset,
2160  pos,
2161  attitude,
2162  posErr,
2163  angErr,
2164  timestamp_ms,
2165  reset_timestamp_ms);
2166 
2167  log_vision_position_estimate_data(usec, x, y, z, roll, pitch, yaw);
2168 }
2169 
2171  const float x,
2172  const float y,
2173  const float z,
2174  const float roll,
2175  const float pitch,
2176  const float yaw)
2177 {
2178  DataFlash_Class::instance()->Log_Write("VISP", "TimeUS,RemTimeUS,PX,PY,PZ,Roll,Pitch,Yaw",
2179  "ssmmmrrr", "FF000000", "QQffffff",
2180  (uint64_t)AP_HAL::micros64(),
2181  (uint64_t)usec,
2182  (double)x,
2183  (double)y,
2184  (double)z,
2185  (double)roll,
2186  (double)pitch,
2187  (double)yaw);
2188 }
2189 
2190 void GCS_MAVLINK::handle_att_pos_mocap(mavlink_message_t *msg)
2191 {
2192  mavlink_att_pos_mocap_t m;
2193  mavlink_msg_att_pos_mocap_decode(msg, &m);
2194 
2195  // sensor assumed to be at 0,0,0 body-frame; need parameters for this?
2196  const Vector3f sensor_offset = {};
2197  const Vector3f pos = {
2198  m.x,
2199  m.y,
2200  m.z
2201  };
2202  Quaternion attitude = Quaternion(m.q);
2203  const float posErr = 0; // parameter required?
2204  const float angErr = 0; // parameter required?
2205  const uint32_t timestamp_ms = m.time_usec * 0.001;
2206  const uint32_t reset_timestamp_ms = 0; // no data available
2207 
2208  AP::ahrs().writeExtNavData(sensor_offset,
2209  pos,
2210  attitude,
2211  posErr,
2212  angErr,
2213  timestamp_ms,
2214  reset_timestamp_ms);
2215 
2216  // calculate euler orientation for logging
2217  float roll;
2218  float pitch;
2219  float yaw;
2220  attitude.to_euler(roll, pitch, yaw);
2221 
2222  log_vision_position_estimate_data(m.time_usec, m.x, m.y, m.z, roll, pitch, yaw);
2223 }
2224 
2225 void GCS_MAVLINK::handle_command_ack(const mavlink_message_t* msg)
2226 {
2227  AP_AccelCal *accelcal = AP::ins().get_acal();
2228  if (accelcal != nullptr) {
2229  accelcal->handleMessage(msg);
2230  }
2231 }
2232 
2233 /*
2234  handle messages which don't require vehicle specific data
2235  */
2236 void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
2237 {
2238  switch (msg->msgid) {
2239  case MAVLINK_MSG_ID_COMMAND_ACK: {
2240  handle_command_ack(msg);
2241  break;
2242  }
2243 
2244  case MAVLINK_MSG_ID_SETUP_SIGNING:
2245  handle_setup_signing(msg);
2246  break;
2247 
2248  case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
2249  FALLTHROUGH;
2250  case MAVLINK_MSG_ID_PARAM_SET:
2251  FALLTHROUGH;
2252  case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
2254  break;
2255 
2256  case MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN:
2258  break;
2259 
2260  case MAVLINK_MSG_ID_DEVICE_OP_READ:
2261  handle_device_op_read(msg);
2262  break;
2263  case MAVLINK_MSG_ID_DEVICE_OP_WRITE:
2265  break;
2266  case MAVLINK_MSG_ID_TIMESYNC:
2267  handle_timesync(msg);
2268  break;
2269  case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
2270  FALLTHROUGH;
2271  case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
2272  FALLTHROUGH;
2273  case MAVLINK_MSG_ID_LOG_ERASE:
2274  FALLTHROUGH;
2275  case MAVLINK_MSG_ID_LOG_REQUEST_END:
2276  FALLTHROUGH;
2277  case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
2279  break;
2280 
2281 
2282  case MAVLINK_MSG_ID_DIGICAM_CONFIGURE:
2283  FALLTHROUGH;
2284  case MAVLINK_MSG_ID_DIGICAM_CONTROL:
2286  break;
2287 
2288  case MAVLINK_MSG_ID_SET_MODE:
2289  handle_set_mode(msg);
2290  break;
2291 
2292  case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
2294  break;
2295 
2296  case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
2297  FALLTHROUGH;
2298  case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
2299  FALLTHROUGH;
2300  case MAVLINK_MSG_ID_MISSION_COUNT:
2301  FALLTHROUGH;
2302  case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
2303  FALLTHROUGH;
2304  case MAVLINK_MSG_ID_MISSION_ITEM:
2305  FALLTHROUGH;
2306  case MAVLINK_MSG_ID_MISSION_ITEM_INT:
2307  FALLTHROUGH;
2308  case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
2309  FALLTHROUGH;
2310  case MAVLINK_MSG_ID_MISSION_REQUEST:
2311  FALLTHROUGH;
2312  case MAVLINK_MSG_ID_MISSION_ACK:
2313  FALLTHROUGH;
2314  case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
2316  break;
2317 
2318  case MAVLINK_MSG_ID_SERIAL_CONTROL:
2319  handle_serial_control(msg);
2320  break;
2321 
2322  case MAVLINK_MSG_ID_GPS_RTCM_DATA:
2323  FALLTHROUGH;
2324  case MAVLINK_MSG_ID_GPS_INPUT:
2325  FALLTHROUGH;
2326  case MAVLINK_MSG_ID_HIL_GPS:
2327  FALLTHROUGH;
2328  case MAVLINK_MSG_ID_GPS_INJECT_DATA:
2330  break;
2331 
2332  case MAVLINK_MSG_ID_STATUSTEXT:
2333  handle_statustext(msg);
2334  break;
2335 
2336  case MAVLINK_MSG_ID_LED_CONTROL:
2337  // send message to Notify
2339  break;
2340 
2341  case MAVLINK_MSG_ID_PLAY_TUNE:
2342  // send message to Notify
2344  break;
2345 
2346  case MAVLINK_MSG_ID_RALLY_POINT:
2347  FALLTHROUGH;
2348  case MAVLINK_MSG_ID_RALLY_FETCH_POINT:
2350  break;
2351 
2352  case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
2354  break;
2355 
2356  case MAVLINK_MSG_ID_DATA96:
2357  handle_data_packet(msg);
2358  break;
2359 
2360  case MAVLINK_MSG_ID_VISION_POSITION_DELTA:
2362  break;
2363 
2364  case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
2366  break;
2367 
2368  case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
2370  break;
2371 
2372  case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE:
2374  break;
2375 
2376  case MAVLINK_MSG_ID_ATT_POS_MOCAP:
2377  handle_att_pos_mocap(msg);
2378  break;
2379  }
2380 
2381 }
2382 
2384 {
2385  AP_Mission *_mission = get_mission();
2386  if (_mission == nullptr) {
2387  return;
2388  }
2389  switch (msg->msgid) {
2390  case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: // MAV ID: 38
2391  {
2392  handle_mission_write_partial_list(*_mission, msg);
2393  break;
2394  }
2395 
2396  // GCS has sent us a mission item, store to EEPROM
2397  case MAVLINK_MSG_ID_MISSION_ITEM: // MAV ID: 39
2398  case MAVLINK_MSG_ID_MISSION_ITEM_INT:
2399  {
2400  if (handle_mission_item(msg, *_mission)) {
2402  }
2403  break;
2404  }
2405 
2406  // read an individual command from EEPROM and send it to the GCS
2407  case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
2408  case MAVLINK_MSG_ID_MISSION_REQUEST: // MAV ID: 40, 51
2409  {
2410  handle_mission_request(*_mission, msg);
2411  break;
2412  }
2413 
2414  case MAVLINK_MSG_ID_MISSION_SET_CURRENT: // MAV ID: 41
2415  {
2416  handle_mission_set_current(*_mission, msg);
2417  break;
2418  }
2419 
2420  // GCS request the full list of commands, we return just the number and leave the GCS to then request each command individually
2421  case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: // MAV ID: 43
2422  {
2423  handle_mission_request_list(*_mission, msg);
2424  break;
2425  }
2426 
2427  // GCS provides the full number of commands it wishes to upload
2428  // individual commands will then be sent from the GCS using the MAVLINK_MSG_ID_MISSION_ITEM message
2429  case MAVLINK_MSG_ID_MISSION_COUNT: // MAV ID: 44
2430  {
2431  handle_mission_count(*_mission, msg);
2432  break;
2433  }
2434 
2435  case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: // MAV ID: 45
2436  {
2437  handle_mission_clear_all(*_mission, msg);
2438  break;
2439  }
2440 
2441  case MAVLINK_MSG_ID_MISSION_ACK:
2442  /* not used */
2443  break;
2444  }
2445 }
2446 
2447 void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t *msg)
2448 {
2450 }
2451 
2453 {
2454  // mark the firmware version in the tlog
2455  const AP_FWVersion &fwver = get_fwver();
2456  send_text(MAV_SEVERITY_INFO, fwver.fw_string);
2457 
2458  if (fwver.middleware_hash_str && fwver.os_hash_str) {
2459  send_text(MAV_SEVERITY_INFO, "PX4: %s NuttX: %s",
2460  fwver.middleware_hash_str, fwver.os_hash_str);
2461  }
2462 
2463  // send system ID if we can
2464  char sysid[40];
2465  if (hal.util->get_system_id(sysid)) {
2466  send_text(MAV_SEVERITY_INFO, sysid);
2467  }
2468 }
2469 
2470 
2472 {
2473 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2474  SITL::SITL *sitl = AP::sitl();
2475  if (sitl == nullptr) {
2476  return;
2477  }
2478  sitl->simstate_send(get_chan());
2479 #endif
2480 }
2481 
2482 MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
2483 {
2485  if (compass == nullptr) {
2486  return MAV_RESULT_UNSUPPORTED;
2487  }
2488 
2489  uint8_t compassNumber = -1;
2490  if (is_equal(packet.param1, 2.0f)) {
2491  compassNumber = 0;
2492  } else if (is_equal(packet.param1, 5.0f)) {
2493  compassNumber = 1;
2494  } else if (is_equal(packet.param1, 6.0f)) {
2495  compassNumber = 2;
2496  }
2497  if (compassNumber == (uint8_t) -1) {
2498  return MAV_RESULT_FAILED;
2499  }
2500  compass->set_and_save_offsets(compassNumber, packet.param2, packet.param3, packet.param4);
2501  return MAV_RESULT_ACCEPTED;
2502 }
2503 
2505 {
2506  AP::ins().init_gyro();
2507  if (!AP::ins().gyro_calibrated_ok_all()) {
2508  return false;
2509  }
2511  return true;
2512 }
2513 
2515 {
2516  // fast barometer calibration
2517  gcs().send_text(MAV_SEVERITY_INFO, "Updating barometer calibration");
2519  gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
2520 
2522  if (airspeed != nullptr) {
2523  airspeed->calibrate(false);
2524  }
2525 
2526  return MAV_RESULT_ACCEPTED;
2527 }
2528 
2529 MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
2530 {
2531  if (is_equal(packet.param1,1.0f)) {
2532  if (!calibrate_gyros()) {
2533  return MAV_RESULT_FAILED;
2534  }
2535  return MAV_RESULT_ACCEPTED;
2536  }
2537 
2538  if (is_equal(packet.param3,1.0f)) {
2540  }
2541 
2542  if (is_equal(packet.param5,1.0f)) {
2543  // start with gyro calibration
2544  if (!calibrate_gyros()) {
2545  return MAV_RESULT_FAILED;
2546  }
2547  // start accel cal
2548  AP::ins().acal_init();
2549  AP::ins().get_acal()->start(this);
2550  return MAV_RESULT_ACCEPTED;
2551  }
2552 
2553  if (is_equal(packet.param5,2.0f)) {
2554  if (!calibrate_gyros()) {
2555  return MAV_RESULT_FAILED;
2556  }
2557  float trim_roll, trim_pitch;
2558  if (!AP::ins().calibrate_trim(trim_roll, trim_pitch)) {
2559  return MAV_RESULT_FAILED;
2560  }
2561  // reset ahrs's trim to suggested values from calibration routine
2562  AP::ahrs().set_trim(Vector3f(trim_roll, trim_pitch, 0));
2563  return MAV_RESULT_ACCEPTED;
2564  }
2565 
2566  if (is_equal(packet.param5,4.0f)) {
2567  // simple accel calibration
2568  return AP::ins().simple_accel_cal();
2569  }
2570 
2571  return MAV_RESULT_UNSUPPORTED;
2572 }
2573 
2574 MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_command_long_t &packet)
2575 {
2576  if (hal.util->get_soft_armed()) {
2577  // *preflight*, remember?
2578  return MAV_RESULT_FAILED;
2579  }
2580  // now call subclass methods:
2582 }
2583 
2584 MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &packet)
2585 {
2587  if (compass == nullptr) {
2588  return MAV_RESULT_UNSUPPORTED;
2589  }
2590  return compass->handle_mag_cal_command(packet);
2591 }
2592 
2593 MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet)
2594 {
2595  if (!is_equal(packet.param1,1.0f)) {
2596  return MAV_RESULT_FAILED;
2597  }
2598 
2600 
2601  return MAV_RESULT_ACCEPTED;
2602 }
2603 
2604 
2605 MAV_RESULT GCS_MAVLINK::handle_command_do_send_banner(const mavlink_command_long_t &packet)
2606 {
2607  send_banner();
2608  return MAV_RESULT_ACCEPTED;
2609 }
2610 
2611 MAV_RESULT GCS_MAVLINK::handle_command_do_set_mode(const mavlink_command_long_t &packet)
2612 {
2613  const MAV_MODE _base_mode = (MAV_MODE)packet.param1;
2614  const uint32_t _custom_mode = (uint32_t)packet.param2;
2615 
2616  return _set_mode_common(_base_mode, _custom_mode);
2617 }
2618 
2619 MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_long_t &packet)
2620 {
2621  if (!AP::ahrs().home_is_set()) {
2622  return MAV_RESULT_FAILED;
2623  }
2624  send_home();
2625  send_ekf_origin();
2626 
2627  return MAV_RESULT_ACCEPTED;
2628 }
2629 
2630 MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet)
2631 {
2632  MAV_RESULT result = MAV_RESULT_FAILED;
2633 
2634  switch (packet.command) {
2635 
2636  case MAV_CMD_DO_SET_MODE:
2637  result = handle_command_do_set_mode(packet);
2638  break;
2639 
2640  case MAV_CMD_DO_SEND_BANNER:
2641  result = handle_command_do_send_banner(packet);
2642  break;
2643 
2644  case MAV_CMD_DO_START_MAG_CAL:
2645  case MAV_CMD_DO_ACCEPT_MAG_CAL:
2646  case MAV_CMD_DO_CANCEL_MAG_CAL: {
2647  result = handle_command_mag_cal(packet);
2648  break;
2649  }
2650 
2651  case MAV_CMD_START_RX_PAIR:
2652  result = handle_rc_bind(packet);
2653  break;
2654 
2655  case MAV_CMD_DO_DIGICAM_CONFIGURE:
2656  FALLTHROUGH;
2657  case MAV_CMD_DO_DIGICAM_CONTROL:
2658  FALLTHROUGH;
2659  case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
2660  result = handle_command_camera(packet);
2661  break;
2662 
2663  case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
2665  break;
2666  }
2667 
2668  case MAV_CMD_PREFLIGHT_CALIBRATION:
2669  result = handle_command_preflight_calibration(packet);
2670  break;
2671 
2672  case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: {
2674  break;
2675  }
2676 
2677  case MAV_CMD_GET_HOME_POSITION:
2678  result = handle_command_get_home_position(packet);
2679  break;
2680 
2681  case MAV_CMD_PREFLIGHT_STORAGE:
2682  if (is_equal(packet.param1, 2.0f)) {
2684  send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board");
2685  result= MAV_RESULT_ACCEPTED;
2686  }
2687  break;
2688 
2689  case MAV_CMD_DO_SET_SERVO:
2690  FALLTHROUGH;
2691  case MAV_CMD_DO_REPEAT_SERVO:
2692  FALLTHROUGH;
2693  case MAV_CMD_DO_SET_RELAY:
2694  FALLTHROUGH;
2695  case MAV_CMD_DO_REPEAT_RELAY:
2696  result = handle_servorelay_message(packet);
2697  break;
2698 
2699  case MAV_CMD_DO_FLIGHTTERMINATION:
2700  result = handle_flight_termination(packet);
2701  break;
2702 
2703  default:
2704  result = MAV_RESULT_UNSUPPORTED;
2705  break;
2706  }
2707 
2708  return result;
2709 }
2710 
2712 {
2714  if (compass == nullptr) {
2715  return true;
2716  }
2717  bool ret = true;
2718  switch (id) {
2719  case MSG_MAG_CAL_PROGRESS:
2720  compass->send_mag_cal_progress(chan);
2721  ret = true;;
2722  break;
2723  case MSG_MAG_CAL_REPORT:
2724  compass->send_mag_cal_report(chan);
2725  ret = true;
2726  break;
2727  default:
2728  ret = true;
2729  break;
2730  }
2731  return ret;
2732 }
2733 
2735 {
2736  AP_Mission *mission = get_mission();
2737  if (mission == nullptr) {
2738  return true;
2739  }
2740 
2741  bool ret = true;
2742  switch (id) {
2743  case MSG_CURRENT_WAYPOINT:
2744  CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
2745  mavlink_msg_mission_current_send(chan, mission->get_current_nav_index());
2746  ret = true;
2747  break;
2749  CHECK_PAYLOAD_SIZE(MISSION_ITEM_REACHED);
2750  mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
2751  ret = true;
2752  break;
2753  case MSG_NEXT_WAYPOINT:
2754  CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
2756  ret = true;
2757  break;
2758  default:
2759  ret = true;
2760  break;
2761  }
2762  return ret;
2763 }
2764 
2766 {
2767  mavlink_msg_hwstatus_send(
2768  chan,
2769  hal.analogin->board_voltage()*1000,
2770  0);
2771 }
2772 
2774 {
2775  bool ret = true;
2776  switch(id) {
2777  case MSG_SYSTEM_TIME:
2778  CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
2779  send_system_time();
2780  ret = true;
2781  break;
2782  case MSG_GPS_RAW:
2783  CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
2785  ret = true;
2786  break;
2787  case MSG_GPS_RTK:
2788  CHECK_PAYLOAD_SIZE(GPS_RTK);
2790  ret = true;
2791  break;
2792  case MSG_GPS2_RAW:
2793  CHECK_PAYLOAD_SIZE(GPS2_RAW);
2795  ret = true;
2796  break;
2797  case MSG_GPS2_RTK:
2798  CHECK_PAYLOAD_SIZE(GPS2_RTK);
2800  ret = true;
2801  break;
2802  default:
2803  ret = true;
2804  break;
2805  }
2806  return ret;
2807 }
2808 
2809 
2811 {
2812  AP_Camera *camera = get_camera();
2813  if (camera == nullptr) {
2814  return true;
2815  }
2816 
2817  bool ret = true;
2818  switch(id) {
2819  case MSG_CAMERA_FEEDBACK:
2820  CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
2821  camera->send_feedback(chan);
2822  ret = true;
2823  break;
2824  default:
2825  ret = true;
2826  break;
2827  }
2828  return ret;
2829 }
2830 
2832 {
2833  const AP_AHRS &ahrs = AP::ahrs();
2834  const Vector3f omega = ahrs.get_gyro();
2835  mavlink_msg_attitude_send(
2836  chan,
2837  AP_HAL::millis(),
2838  ahrs.roll,
2839  ahrs.pitch,
2840  ahrs.yaw,
2841  omega.x,
2842  omega.y,
2843  omega.z);
2844 }
2845 
2847  return global_position_current_loc.alt * 10UL;
2848 }
2850  float posD;
2852  posD *= -1000.0f; // change from down to up and metres to millimeters
2853  return posD;
2854 }
2856 {
2857  AP_AHRS &ahrs = AP::ahrs();
2858 
2859  ahrs.get_position(global_position_current_loc); // return value ignored; we send stale data
2860 
2861  Vector3f vel;
2862  ahrs.get_velocity_NED(vel);
2863 
2864  mavlink_msg_global_position_int_send(
2865  chan,
2866  AP_HAL::millis(),
2867  global_position_current_loc.lat, // in 1E7 degrees
2868  global_position_current_loc.lng, // in 1E7 degrees
2869  global_position_int_alt(), // millimeters above ground/sea level
2870  global_position_int_relative_alt(), // millimeters above ground/sea level
2871  vel.x * 100, // X speed cm/s (+ve North)
2872  vel.y * 100, // Y speed cm/s (+ve East)
2873  vel.z * 100, // Z speed cm/s (+ve Down)
2874  ahrs.yaw_sensor); // compass heading in 1/100 degree
2875 }
2876 
2878 {
2879  if (telemetry_delayed()) {
2880  return false;
2881  }
2882 
2883  bool ret = true;
2884 
2885  switch(id) {
2886 
2887  case MSG_ATTITUDE:
2888  CHECK_PAYLOAD_SIZE(ATTITUDE);
2889  send_attitude();
2890  break;
2891 
2892  case MSG_NEXT_PARAM:
2893  CHECK_PAYLOAD_SIZE(PARAM_VALUE);
2895  ret = true;
2896  break;
2897 
2898  case MSG_HEARTBEAT:
2899  CHECK_PAYLOAD_SIZE(HEARTBEAT);
2901  send_heartbeat();
2902  break;
2903 
2904  case MSG_HWSTATUS:
2905  CHECK_PAYLOAD_SIZE(HWSTATUS);
2906  send_hwstatus();
2907  ret = true;
2908  break;
2909 
2910  case MSG_LOCATION:
2911  CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);
2913  break;
2914 
2915  case MSG_CURRENT_WAYPOINT:
2916  FALLTHROUGH;
2918  FALLTHROUGH;
2919  case MSG_NEXT_WAYPOINT:
2920  ret = try_send_mission_message(id);
2921  break;
2922 
2923  case MSG_MAG_CAL_PROGRESS:
2924  FALLTHROUGH;
2925  case MSG_MAG_CAL_REPORT:
2926  ret = try_send_compass_message(id);
2927  break;
2928 
2929  case MSG_BATTERY_STATUS:
2931  break;
2932 
2933  case MSG_BATTERY2:
2934  CHECK_PAYLOAD_SIZE(BATTERY2);
2935  send_battery2();
2936  break;
2937 
2938  case MSG_EXTENDED_STATUS2:
2939  CHECK_PAYLOAD_SIZE(MEMINFO);
2940  send_meminfo();
2941  ret = true;
2942  break;
2943 
2944  case MSG_RANGEFINDER:
2945  CHECK_PAYLOAD_SIZE(RANGEFINDER);
2947  ret = send_distance_sensor();
2948  ret = ret && send_proximity();
2949  break;
2950 
2951  case MSG_CAMERA_FEEDBACK:
2952  ret = try_send_camera_message(id);
2953  break;
2954 
2955  case MSG_GPS_RAW:
2956  FALLTHROUGH;
2957  case MSG_GPS_RTK:
2958  FALLTHROUGH;
2959  case MSG_GPS2_RAW:
2960  FALLTHROUGH;
2961  case MSG_GPS2_RTK:
2962  FALLTHROUGH;
2963  case MSG_SYSTEM_TIME:
2964  ret = try_send_gps_message(id);
2965  break;
2966 
2967  case MSG_LOCAL_POSITION:
2968  CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
2970  break;
2971 
2973  CHECK_PAYLOAD_SIZE(POSITION_TARGET_GLOBAL_INT);
2975  break;
2976 
2977  case MSG_RADIO_IN:
2978  CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
2979  send_radio_in();
2980  break;
2981 
2982  case MSG_RAW_IMU1:
2983  CHECK_PAYLOAD_SIZE(RAW_IMU);
2984  send_raw_imu();
2985  break;
2986 
2987  case MSG_RAW_IMU2:
2988  CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
2990  break;
2991 
2992  case MSG_RAW_IMU3:
2993  CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
2995  break;
2996 
2997  case MSG_SERVO_OUTPUT_RAW:
2998  CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
3000  break;
3001 
3002  case MSG_SIMSTATE:
3003  CHECK_PAYLOAD_SIZE(SIMSTATE);
3004  send_simstate();
3005  CHECK_PAYLOAD_SIZE(AHRS2);
3006  send_ahrs2();
3007  break;
3008 
3009  case MSG_AHRS:
3010  CHECK_PAYLOAD_SIZE(AHRS);
3011  send_ahrs();
3012  break;
3013 
3014  case MSG_VFR_HUD:
3015  CHECK_PAYLOAD_SIZE(VFR_HUD);
3016  send_vfr_hud();
3017  break;
3018 
3019  case MSG_VIBRATION:
3020  CHECK_PAYLOAD_SIZE(VIBRATION);
3021  send_vibration();
3022  break;
3023 
3024  default:
3025  // try_send_message must always at some stage return true for
3026  // a message, or we will attempt to infinitely retry the
3027  // message as part of send_message.
3028  // This message will be sent out at the same rate as the
3029  // unknown message, so should be safe.
3030  gcs().send_text(MAV_SEVERITY_DEBUG, "Sending unknown message (%u)", id);
3031 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3032  AP_HAL::panic("Sending unknown ap_message %u", id);
3033 #endif
3034  ret = true;
3035  break;
3036  }
3037 
3038  return ret;
3039 }
3040 
3042 {
3043  if (waypoint_receiving) {
3044  // don't interfere with mission transfer
3045  return;
3046  }
3047 
3048  if (!hal.scheduler->in_delay_callback()) {
3049  // DataFlash_Class will not send log data if we are armed.
3051  }
3052 
3053  gcs().set_out_of_time(false);
3054 
3056 
3057  if (gcs().out_of_time()) return;
3058 
3059  if (hal.scheduler->in_delay_callback()) {
3060  if (in_hil_mode()) {
3061  // in HIL we need to keep sending servo values to ensure
3062  // the simulator doesn't pause, otherwise our sensor
3063  // calibration could stall
3066  }
3069  }
3070  }
3071  // send no other streams while in delay, just in case they
3072  // take way too long to run
3073  return;
3074  }
3075 
3076  for (uint8_t i=0; all_stream_entries[i].ap_message_ids != nullptr; i++) {
3077  const streams id = (streams)all_stream_entries[i].stream_id;
3078  if (!stream_trigger(id)) {
3079  continue;
3080  }
3081  const ap_message *msg_ids = all_stream_entries[i].ap_message_ids;
3082  for (uint8_t j=0; j<all_stream_entries[i].num_ap_message_ids; j++) {
3083  const ap_message msg_id = msg_ids[j];
3084  send_message(msg_id);
3085  }
3086  if (gcs().out_of_time()) {
3087  break;
3088  }
3089  }
3090 }
3091 
3092 /*
3093  correct an offboard timestamp in microseconds into a local timestamp
3094  since boot in milliseconds. This is a transport lag correction function, and works by assuming two key things:
3095 
3096  1) the data did not come from the future in our time-domain
3097  2) the data is not older than max_lag_ms in our time-domain
3098 
3099  It works by estimating the transport lag by looking for the incoming
3100  packet that had the least lag, and converging on the offset that is
3101  associated with that lag
3102 
3103  Return a value in milliseconds since boot (for use by the EKF)
3104  */
3105 uint32_t GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size)
3106 {
3107  const uint32_t max_lag_us = 500*1000UL;
3108  uint64_t local_us;
3109  // if the HAL supports it then constrain the latest possible time
3110  // the packet could have been sent by the uart receive time and
3111  // the baudrate and packet size.
3112  uint64_t uart_receive_time = _port->receive_time_constraint_us(payload_size);
3113  if (uart_receive_time != 0) {
3114  local_us = uart_receive_time;
3115  } else {
3116  local_us = AP_HAL::micros64();
3117  }
3118  int64_t diff_us = int64_t(local_us) - int64_t(offboard_usec);
3119 
3120  if (!lag_correction.initialised ||
3121  diff_us < lag_correction.link_offset_usec) {
3122  // this message arrived from the remote system with a
3123  // timestamp that would imply the message was from the
3124  // future. We know that isn't possible, so we adjust down the
3125  // correction value
3126  lag_correction.link_offset_usec = diff_us;
3127 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3128  printf("link_offset_usec=%lld\n", (long long int)diff_us);
3129 #endif
3130  lag_correction.initialised = true;
3131  }
3132 
3133  int64_t estimate_us = offboard_usec + lag_correction.link_offset_usec;
3134 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3135  if (estimate_us > (int64_t)local_us) {
3136  // this should be impossible, just check it under SITL
3137  printf("msg from future %lld\n", (long long int)(estimate_us - local_us));
3138  }
3139 #endif
3140 
3141  if (estimate_us + max_lag_us < int64_t(local_us)) {
3142  // this implies the message came from too far in the past. Clamp the lag estimate
3143  // to assume the message had maximum lag
3144  estimate_us = local_us - max_lag_us;
3145  lag_correction.link_offset_usec = estimate_us - offboard_usec;
3146 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3147  printf("offboard timestammp too old %lld\n", (long long int)(local_us - estimate_us));
3148 #endif
3149  }
3150 
3151  if (lag_correction.min_sample_counter == 0) {
3152  lag_correction.min_sample_us = diff_us;
3153  }
3154  lag_correction.min_sample_counter++;
3155  if (diff_us < lag_correction.min_sample_us) {
3156  lag_correction.min_sample_us = diff_us;
3157  }
3158  if (lag_correction.min_sample_counter == 200) {
3159  // we have 200 samples of the transport lag. To
3160  // account for long term clock drift we set the diff we will
3161  // use in future to this value
3162  lag_correction.link_offset_usec = lag_correction.min_sample_us;
3163  lag_correction.min_sample_counter = 0;
3164 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3165  printf("new link_offset_usec=%lld\n", (long long int)(lag_correction.min_sample_us));
3166 #endif
3167  }
3168 
3169  return estimate_us / 1000U;
3170 }
3171 
3173 {
3174  return *GCS::instance();
3175 }
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
static AP_Baro barometer
Definition: AHRS_Test.cpp:23
virtual uint32_t available_memory(void)
Definition: Util.h:121
int printf(const char *fmt,...)
Definition: stdio.c:113
bool get_soft_armed() const
Definition: Util.h:15
virtual bool get_hagl(float &height) const
Definition: AP_AHRS.h:270
void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t *msg)
Definition: DataFlash.cpp:557
virtual bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS.h:309
Compass & compass()
static void handle_led_control(mavlink_message_t *msg)
Definition: AP_Notify.cpp:300
AP_RangeFinder_Backend * get_backend(uint8_t id) const
static bool mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command &cmd, mavlink_mission_item_int_t &packet)
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
static uint8_t get_valid_channel_count(void)
bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const
float roll
Definition: AP_AHRS.h:224
static uint8_t counter
Jump_Command jump
Definition: AP_Mission.h:197
virtual void force_safety_no_wait(void)
Definition: RCOutput.h:103
uint8_t num_instances(void) const
Definition: AP_Baro.h:158
uint16_t voltage_mv() const
Vector3< float > Vector3f
Definition: vector3.h:246
#define PROXIMITY_SENSOR_ID_START
Definition: AP_Proximity.h:28
Definition: GCS.h:60
bool gcs_terminate(bool should_terminate, const char *reason)
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
Definition: Util.h:102
void update_calibration(void)
Definition: AP_Baro.cpp:246
float get_declination() const
virtual void setup_uarts(AP_SerialManager &serial_manager)
void send_mission_item_reached_message(uint16_t mission_index)
#define CHECK_PAYLOAD_SIZE(id)
Definition: GCS.h:29
virtual float board_voltage(void)=0
virtual void force_safety_off(void)
Definition: RCOutput.h:98
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
enum Rotation orientation() const
virtual const Vector3f & get_gyro(void) const =0
uint8_t activeCores(void) const
Definition: AP_NavEKF2.h:50
virtual uint16_t read(uint8_t ch)=0
#define FALLTHROUGH
Definition: AP_Common.h:50
uint16_t distance_cm() const
SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const
AP_HAL::UARTDriver * console
Definition: HAL.h:110
virtual void begin(uint32_t baud)=0
void control_msg(const mavlink_message_t *msg)
decode deprecated MavLink message that controls camera.
Definition: AP_Camera.cpp:181
const Vector3f & get_gyro(uint8_t i) const
float get_temperature(void) const
Definition: AP_Baro.h:63
#define RANGEFINDER_MAX_INSTANCES
Definition: RangeFinder.h:24
bool get_upward_distance(uint8_t instance, float &distance) const
virtual bool get_position(struct Location &loc) const =0
virtual bool get_relative_position_NED_home(Vector3f &vec) const
Definition: AP_AHRS.h:326
virtual uint8_t capacity_remaining_pct(uint8_t instance) const
capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
Interface definition for the various Ground Control System.
Object managing Mission.
Definition: AP_Mission.h:45
uint16_t get_current_nav_index() const
Definition: AP_Mission.h:389
mavlink_statustext_t msg
Definition: GCS.h:643
GCS & gcs()
static RangeFinder * get_singleton(void)
Definition: RangeFinder.h:167
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
void truncate(uint16_t index)
truncate - truncate any mission items beyond given index
Definition: AP_Mission.cpp:197
void send_mavlink_gps2_raw(mavlink_channel_t chan)
Definition: AP_GPS.cpp:942
float get_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:53
uint16_t num_commands() const
Definition: AP_Mission.h:330
virtual float get_error_yaw(void) const =0
void set_and_save_offsets(uint8_t i, const Vector3f &offsets)
AP_RangeFinder_Backend * find_instance(enum Rotation orientation) const
void Log_Write_Message(const char *message)
Definition: DataFlash.cpp:593
void getEulerAngles(int8_t instance, Vector3f &eulers) const
float pitch
Definition: AP_AHRS.h:225
ap_message
Definition: GCS.h:37
#define PROXIMITY_MAX_DIRECTION
Definition: AP_Proximity.h:27
AP_HAL::Util * util
Definition: HAL.h:115
void set_capabilities(uint64_t cap)
Definition: Util.h:17
void data_stream_send()
virtual void reset_gyro_drift(void)=0
const char * os_hash_str
Definition: AP_FWVersion.h:14
void service_statustext(void)
const AP_FWVersion fwver
Definition: routing.cpp:16
void from_euler(float roll, float pitch, float yaw)
Definition: quaternion.cpp:130
void * __brkval
Definition: syscalls.c:71
void handle_msg(mavlink_message_t *msg)
float yaw
Definition: AP_AHRS.h:226
static bool receiver_bind(const int dsmMode)
global GCS object
Definition: GCS.h:562
void Log_Write_Radio(const mavlink_radio_t &packet)
Definition: LogFile.cpp:1296
bool add_cmd(Mission_Command &cmd)
Definition: AP_Mission.cpp:254
void Log_Write_Home_And_Origin()
Definition: AP_AHRS.cpp:462
virtual bool usb_connected(void)=0
const char * result
Definition: Printf.cpp:16
const Mission_Command & get_current_nav_cmd() const
get_current_nav_cmd - returns the current "navigation" command
Definition: AP_Mission.h:384
const char * name
Definition: BusTest.cpp:11
AP_RSSI * rssi()
Definition: AP_RSSI.cpp:220
void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
uint8_t minor
Definition: AP_FWVersion.h:8
Rotation
Definition: rotations.h:27
const char * middleware_hash_str
Definition: AP_FWVersion.h:13
static AP_Notify * instance(void)
Definition: AP_Notify.h:50
float distance_max() const
uint16_t cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
#define MIN(a, b)
Definition: usb_conf.h:215
bool clear()
Definition: AP_Mission.cpp:175
bool healthy() const
Definition: OpticalFlow.h:46
virtual uint16_t power_status_flags(void)
Definition: AnalogIn.h:52
virtual bool have_inertial_nav(void) const
Definition: AP_AHRS.h:470
bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const
Definition: AP_Mission.cpp:453
const Vector2f & flowRate() const
Definition: OpticalFlow.h:55
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
static GCS * _singleton
Definition: GCS.h:639
SITL::SITL * sitl()
Definition: SITL.cpp:229
bool replace_cmd(uint16_t index, Mission_Command &cmd)
Definition: AP_Mission.cpp:272
uint8_t major
Definition: AP_FWVersion.h:7
const Vector3f & get_accel(uint8_t i) const
uint8_t num_sensors(void) const
Definition: AP_Proximity.h:84
float consumed_wh(uint8_t instance) const
consumed_wh - returns total energy drawn since start-up in watt.hours
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
Definition: AP_Compass.h:122
MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet)
static bool mission_cmd_to_mavlink(const AP_Mission::Mission_Command &cmd, mavlink_mission_item_t &packet)
Definition: AP_Mission.cpp:973
static AP_Radio * instance(void)
Definition: AP_Radio.h:89
virtual void delay(uint16_t ms)=0
T y
Definition: vector2.h:37
static MAV_MISSION_RESULT mavlink_to_mission_cmd(const mavlink_mission_item_t &packet, AP_Mission::Mission_Command &cmd)
Definition: AP_Mission.cpp:922
void send_message(enum ap_message id)
void send_mag_cal_report(mavlink_channel_t chan)
#define HAVE_PAYLOAD_SPACE(chan, id)
Definition: GCS.h:28
Proximity_Type get_type(uint8_t instance) const
const char * fw_string
Definition: AP_FWVersion.h:11
#define x(i)
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
Definition: Util.cpp:53
void send_mavlink_gps_raw(mavlink_channel_t chan)
Definition: AP_GPS.cpp:899
static SRV_Channel * srv_channel(uint8_t i)
Definition: SRV_Channel.h:405
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual void set_trim(Vector3f new_trim)
Definition: AP_AHRS.cpp:190
uint8_t read_receiver_rssi_uint8()
Definition: AP_RSSI.cpp:161
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
Definition: AP_AHRS.h:569
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
#define GRAVITY_MSS
Definition: definitions.h:47
static void erase_all(void)
Definition: AP_Param.cpp:109
Proximity_Status get_status(uint8_t instance) const
float get_ground_pressure(void) const
Definition: AP_Baro.h:107
#define f(i)
const char * fmt
Definition: Printf.cpp:14
static OpticalFlow optflow
uint8_t quality() const
Definition: OpticalFlow.h:52
bool has_current(uint8_t instance) const
has_current - returns true if battery monitor instance provides current info
T y
Definition: vector3.h:67
void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
Definition: AP_GPS.cpp:971
const NavEKF2 & get_NavEKF2_const(void) const
virtual size_t write(uint8_t)=0
uint8_t bitmask
Definition: GCS.h:642
void queue_message(MAV_SEVERITY severity, const char *text)
uint32_t millis()
Definition: system.cpp:157
const Vector3f & get_offsets(uint8_t i) const
Definition: AP_Compass.h:166
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
const Vector3f & get_gyro_offsets(uint8_t i) const
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time)
Definition: AP_Camera.cpp:189
void handleMessage(const mavlink_message_t *msg)
void set_out_of_time(bool val)
Definition: GCS.h:608
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
FIRMWARE_VERSION_TYPE fw_type
Definition: AP_FWVersion.h:10
virtual const Vector3f & get_gyro_drift(void) const =0
uint64_t micros64()
Definition: system.cpp:162
virtual float servorail_voltage(void)
Definition: AnalogIn.h:49
void calibrate(bool in_startup)
bool check_latlng(float lat, float lng)
Definition: location.cpp:231
bool set_current_cmd(uint16_t index)
Definition: AP_Mission.cpp:339
virtual void set_flow_control(enum flow_control flow_control_setting)
Definition: UARTDriver.h:50
uint32_t get_accel_clip_count(uint8_t instance) const
float current_amps(uint8_t instance) const
current_amps - returns the instantaneous current draw in amperes
virtual bool get_system_id(char buf[40])
Definition: Util.h:68
virtual float get_error_rp(void) const =0
virtual bool force_safety_on(void)
Definition: RCOutput.h:93
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
float get_pressure(void) const
Definition: AP_Baro.h:59
virtual int16_t read()=0
void simstate_send(mavlink_channel_t chan)
Definition: SITL.cpp:126
void send_feedback(mavlink_channel_t chan)
Definition: AP_Camera.cpp:243
const Vector2f & bodyRate() const
Definition: OpticalFlow.h:58
static Compass compass
Definition: AHRS_Test.cpp:20
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
MAV_RESULT simple_accel_cal()
static void handle_play_tune(mavlink_message_t *msg)
Definition: AP_Notify.cpp:310
float get_differential_pressure(uint8_t i) const
Definition: AP_Airspeed.h:99
#define NULL
Definition: hal_types.h:59
static AP_Proximity * get_singleton(void)
Definition: AP_Proximity.h:135
AP_BattMonitor & battery()
static AP_Airspeed * get_singleton()
Definition: AP_Airspeed.h:170
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
uint16_t num_commands_max() const
num_commands_max - returns maximum number of commands that can be stored
uint8_t get_count(void) const
Definition: AP_Compass.h:119
uint8_t orientation[PROXIMITY_MAX_DIRECTION]
Definition: AP_Proximity.h:61
#define PAYLOAD_SIZE(chan, id)
Definition: GCS.h:27
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
T x
Definition: vector2.h:37
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
virtual void reboot(bool hold_in_bootloader)=0
Catch-all header that defines all supported optical flow classes.
float distance[PROXIMITY_MAX_DIRECTION]
Definition: AP_Proximity.h:62
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
static const uint8_t num_gcs
Definition: routing.cpp:56
const char * fw_hash_str
Definition: AP_FWVersion.h:12
void set_trigger_distance(uint32_t distance_m)
Definition: AP_Camera.h:60
virtual uint64_t receive_time_constraint_us(uint16_t nbytes)
Definition: UARTDriver.h:87
uint16_t get_output_pwm(void) const
Definition: SRV_Channel.h:139
MAV_COLLISION_THREAT_LEVEL threat_level
Definition: AP_Avoidance.h:54
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
virtual enum flow_control get_flow_control(void)
Definition: UARTDriver.h:51
void handle_msg(const mavlink_message_t *msg)
Definition: AP_GPS.cpp:789
AP_HAL::GPIO * gpio
Definition: HAL.h:111
static class GCS * instance()
Definition: GCS.h:579
static MAV_MISSION_RESULT mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t &packet, AP_Mission::Mission_Command &cmd)
Definition: AP_Mission.cpp:577
uint64_t get_capabilities() const
Definition: Util.h:19
AP_AccelCal * get_acal() const
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
static uint16_t get_radio_in(const uint8_t chan)
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
virtual bool get_origin(Location &ret) const
Definition: AP_AHRS.h:464
virtual bool get_secondary_attitude(Vector3f &eulers) const
Definition: AP_AHRS.h:419
const Vector3f & get_accel_offsets(uint8_t i) const
float value
uint8_t get_gyro_count(void) const
void Log_Write_EntireMission(const AP_Mission &mission)
Definition: DataFlash.cpp:588
bool get_temperature(float &temperature) const
float groundspeed(void)
Definition: AP_AHRS.h:359
void send_mag_cal_progress(mavlink_channel_t chan)
void update()
AP_InertialSensor & ins()
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
void send_text(const char *str)
Definition: AP_Notify.cpp:326
int16_t min_distance_cm() const
float distance_min() const
AP_Baro & baro()
Definition: AP_Baro.cpp:737
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool has_consumed_energy(uint8_t instance) const
has_consumed_energy - returns true if battery monitor instance provides consumed energy info ...
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
Definition: AP_Camera.cpp:214
uint8_t num_instances(void) const
float voltage(uint8_t instance) const
voltage - returns battery voltage in millivolts
float consumed_mah(uint8_t instance) const
consumed_mah - returns total current drawn since start-up in milliampere.hours
Vector3f get_vibration_levels() const
int32_t yaw_sensor
Definition: AP_AHRS.h:231
bool healthy(uint8_t i) const
Definition: AP_Airspeed.h:135
void handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
Definition: AP_Mount.cpp:617
void start(GCS_MAVLINK *gcs)
virtual void get_relative_position_D_home(float &posD) const =0
virtual bool set_origin(const Location &loc)
Definition: AP_AHRS.h:461
uint32_t micros()
Definition: system.cpp:152
bool getLLH(struct Location &loc) const
Definition: AP_NavEKF2.cpp:980
void retry_deferred()
void zero()
Definition: vector3.h:182
virtual bool in_delay_callback() const
Definition: Scheduler.h:44
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67
uint8_t get_accel_count(void) const
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
int16_t max_distance_cm() const
const cells & get_cell_voltages() const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14