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> 34 #if HAL_RCINPUT_WITH_AP_RADIO 39 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 91 uart = serial_manager.
find_serial(protocol, instance);
92 if (uart ==
nullptr) {
98 mavlink_channel_t mav_chan;
115 for (uint8_t i=0; i<3; i++) {
129 init(uart, mav_chan);
132 mavlink_status_t *status = mavlink_get_channel_status(
chan);
133 if (status ==
nullptr) {
141 if (status->signing ==
nullptr) {
143 status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
149 status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
152 if (
chan == MAVLINK_COMM_0) {
155 status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
170 mavlink_msg_mission_request_send(
175 MAV_MISSION_TYPE_MISSION);
183 mavlink_msg_meminfo_send(
chan, __brkval,
MIN(memory, 0xFFFFU), memory);
189 mavlink_msg_power_status_send(
chan,
196 const uint8_t instance)
const 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");
204 mavlink_msg_battery_status_send(
chan,
206 MAV_BATTERY_FUNCTION_UNKNOWN,
207 MAV_BATTERY_TYPE_UNKNOWN,
208 got_temperature ? ((int16_t) (temp * 100)) : INT16_MAX,
234 mavlink_msg_distance_sensor_send(
249 if (rangefinder ==
nullptr) {
255 bool filter_possible_proximity_sensors =
false;
257 if (proximity !=
nullptr) {
258 for (uint8_t i = 0; i < proximity->
num_sensors(); i++) {
260 filter_possible_proximity_sensors =
true;
268 if (sensor ==
nullptr) {
272 if (!filter_possible_proximity_sensors ||
283 if (rangefinder ==
nullptr) {
290 mavlink_msg_rangefinder_send(
303 const uint16_t dist_min = (uint16_t)(proximity->
distance_min() * 100.0f);
304 const uint16_t dist_max = (uint16_t)(proximity->
distance_max() * 100.0f);
310 mavlink_msg_distance_sensor_send(
315 (uint16_t)(dist_array.
distance[i] * 100.0f),
316 MAV_DISTANCE_SENSOR_LASER,
327 mavlink_msg_distance_sensor_send(
332 (uint16_t)(dist_up * 100.0
f),
333 MAV_DISTANCE_SENSOR_LASER,
335 MAV_SENSOR_ROTATION_PITCH_90,
344 #if AP_AHRS_NAVEKF_AVAILABLE 349 mavlink_msg_ahrs2_send(
chan,
363 mavlink_msg_ahrs3_send(
chan,
381 mavlink_mission_request_list_t packet;
382 mavlink_msg_mission_request_list_decode(msg, &packet);
385 mavlink_msg_mission_count_send(
chan,msg->sysid, msg->compid, mission.
num_commands(),
386 MAV_MISSION_TYPE_MISSION);
399 if (msg->msgid == MAVLINK_MSG_ID_MISSION_REQUEST_INT) {
401 mavlink_mission_request_int_t packet;
402 mavlink_msg_mission_request_int_decode(msg, &packet);
406 goto mission_item_send_failed;
409 mavlink_mission_item_int_t ret_packet;
410 memset(&ret_packet, 0,
sizeof(ret_packet));
412 goto mission_item_send_failed;
417 ret_packet.current = 1;
419 ret_packet.current = 0;
423 ret_packet.autocontinue = 1;
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;
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);
443 mavlink_mission_request_t packet;
444 mavlink_msg_mission_request_decode(msg, &packet);
446 if (packet.seq != 0 &&
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;
456 goto mission_item_send_failed;
459 mavlink_mission_item_t ret_packet;
460 memset(&ret_packet, 0,
sizeof(ret_packet));
462 goto mission_item_send_failed;
467 ret_packet.current = 1;
469 ret_packet.current = 0;
473 ret_packet.autocontinue = 1;
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;
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);
495 mission_item_send_failed:
497 mavlink_msg_mission_ack_send(
chan, msg->sysid, msg->compid, MAV_MISSION_ERROR,
498 MAV_MISSION_TYPE_MISSION);
507 mavlink_mission_set_current_t packet;
508 mavlink_msg_mission_set_current_decode(msg, &packet);
512 mavlink_msg_mission_current_send(
chan, packet.seq);
522 mavlink_mission_count_t packet;
523 mavlink_msg_mission_count_decode(msg, &packet);
528 mavlink_msg_mission_ack_send(
chan, msg->sysid, msg->compid, MAV_MISSION_NO_SPACE,
529 MAV_MISSION_TYPE_MISSION);
553 mavlink_mission_clear_all_t packet;
554 mavlink_msg_mission_clear_all_decode(msg, &packet);
557 if (mission.
clear()) {
559 mavlink_msg_mission_ack_send(
chan, msg->sysid, msg->compid, MAV_MISSION_ACCEPTED,
560 MAV_MISSION_TYPE_MISSION);
563 mavlink_msg_mission_ack_send(
chan, msg->sysid, msg->compid, MAV_MISSION_ERROR,
564 MAV_MISSION_TYPE_MISSION);
574 mavlink_mission_write_partial_list_t packet;
575 mavlink_msg_mission_write_partial_list_decode(msg, &packet);
578 if ((
unsigned)packet.start_index > mission.
num_commands() ||
580 packet.end_index < packet.start_index) {
581 send_text(MAV_SEVERITY_WARNING,
"Flight plan update rejected");
607 char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
609 va_start(arg_list, fmt);
610 hal.
util->
vsnprintf((
char *)text,
sizeof(text), fmt, arg_list);
612 text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = 0;
618 mavlink_radio_t packet;
619 mavlink_msg_radio_decode(msg, &packet);
623 if (packet.remrssi != 0) {
656 MAV_MISSION_RESULT
result = MAV_MISSION_ACCEPTED;
658 bool mission_is_complete =
false;
660 uint16_t current = 0;
662 if (msg->msgid == MAVLINK_MSG_ID_MISSION_ITEM) {
663 mavlink_mission_item_t packet;
664 mavlink_msg_mission_item_decode(msg, &packet);
668 if (result != MAV_MISSION_ACCEPTED) {
673 current = packet.current;
675 mavlink_mission_item_int_t packet;
676 mavlink_msg_mission_item_int_decode(msg, &packet);
680 if (result != MAV_MISSION_ACCEPTED) {
685 current = packet.current;
692 : MAV_MISSION_ERROR) ;
704 result = MAV_MISSION_ACCEPTED;
710 result = MAV_MISSION_ERROR;
716 result = MAV_MISSION_INVALID_SEQUENCE;
721 if (cmd.
id == MAV_CMD_DO_JUMP) {
723 result = MAV_MISSION_ERROR;
731 result = MAV_MISSION_ACCEPTED;
733 result = MAV_MISSION_ERROR;
739 result = MAV_MISSION_ACCEPTED;
741 result = MAV_MISSION_ERROR;
746 result = MAV_MISSION_ERROR;
755 mavlink_msg_mission_ack_send_buf(
760 MAV_MISSION_ACCEPTED,
761 MAV_MISSION_TYPE_MISSION);
763 send_text(MAV_SEVERITY_INFO,
"Flight plan received");
765 mission_is_complete =
true;
777 return mission_is_complete;
781 mavlink_msg_mission_ack_send_buf(
787 MAV_MISSION_TYPE_MISSION);
789 return mission_is_complete;
798 next_deferred_message++;
800 next_deferred_message = 0;
852 num_deferred_messages++;
856 mavlink_message_t &msg)
860 if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
863 if (!(status.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) &&
864 (status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) &&
870 mavlink_status_t *cstatus = mavlink_get_channel_status(
chan);
871 if (cstatus !=
nullptr) {
872 cstatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
885 mavlink_message_t msg;
886 mavlink_status_t status;
892 status.packet_rx_drop_count = 0;
896 for (uint16_t i=0; i<nbytes; i++)
898 const uint8_t c = (uint8_t)
_port->
read();
899 const uint32_t protocol_timeout = 4000;
902 now_ms -
alternative.last_mavlink_ms > protocol_timeout) {
917 if (now_ms -
alternative.last_alternate_ms <= protocol_timeout) {
922 bool parsed_packet =
false;
925 if (mavlink_parse_char(
chan, c, &msg, &status)) {
929 parsed_packet =
true;
934 if (parsed_packet || i % 100 == 0) {
978 mavlink_msg_system_time_send(
991 uint8_t receiver_rssi = 0;
992 if (rssi !=
nullptr) {
997 mavlink_status_t *status = mavlink_get_channel_status(
chan);
1002 if (status && (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
1004 mavlink_msg_rc_channels_raw_send(
1022 mavlink_msg_rc_channels_send(
1061 mavlink_msg_raw_imu_send(
1089 mavlink_msg_scaled_imu2_send(
1117 mavlink_msg_scaled_imu3_send(
1144 mavlink_msg_scaled_pressure3_send(
1157 float diff_pressure = 0;
1160 if (airspeed !=
nullptr) {
1164 mavlink_msg_scaled_pressure_send(
1168 diff_pressure*0.01f,
1174 mavlink_msg_scaled_pressure2_send(
1193 if (counter++ < 10) {
1204 mavlink_msg_sensor_offsets_send(
chan,
1223 mavlink_msg_ahrs_send(
1239 if (dataflash_p !=
nullptr) {
1240 dataflash_p->Log_Write_Message(text);
1251 if (!statustext.bitmask) {
1256 statustext.msg.severity = severity;
1257 strncpy(statustext.msg.text, text,
sizeof(statustext.msg.text));
1262 _statustext_queue.push_force(statustext);
1265 service_statustext();
1286 if (_statustext_queue.empty()) {
1291 for (uint8_t idx=0; idx<_status_capacity; ) {
1293 if (statustext ==
nullptr) {
1299 uint8_t chan_bit = (1U<<i);
1301 if (statustext->
bitmask & chan_bit) {
1303 mavlink_channel_t chan_index = (mavlink_channel_t)(MAVLINK_COMM_0+i);
1306 mavlink_msg_statustext_send(chan_index, statustext->
msg.severity, statustext->
msg.text);
1307 statustext->
bitmask &= ~chan_bit;
1312 if (statustext->
bitmask == 0) {
1313 _statustext_queue.remove(idx);
1323 for (uint8_t i=0; i<
num_gcs(); i++) {
1324 if (
chan(i).initialised) {
1325 chan(i).send_message(
id);
1332 for (uint8_t i=0; i<
num_gcs(); i++) {
1333 if (
chan(i).initialised) {
1334 chan(i).retry_deferred();
1337 service_statustext();
1342 for (uint8_t i=0; i<
num_gcs(); i++) {
1343 if (
chan(i).initialised) {
1344 chan(i).data_stream_send();
1351 for (uint8_t i=0; i<
num_gcs(); i++) {
1352 if (
chan(i).initialised) {
1360 for (uint8_t i=0; i<
num_gcs(); i++) {
1361 if (
chan(i).initialised) {
1362 chan(i).mission_item_reached_index = mission_index;
1387 mavlink_msg_battery2_send(
chan, battery.
voltage(1)*1000, current);
1396 mavlink_set_mode_t packet;
1397 mavlink_msg_set_mode_decode(msg, &packet);
1399 const MAV_MODE _base_mode = (MAV_MODE)packet.base_mode;
1400 const uint32_t _custom_mode = packet.custom_mode;
1405 mavlink_msg_command_ack_send_buf(msg,
chan, MAVLINK_MSG_ID_SET_MODE,
result);
1413 MAV_RESULT
result = MAV_RESULT_UNSUPPORTED;
1415 if (_base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
1417 result = MAV_RESULT_ACCEPTED;
1419 }
else if (_base_mode == (MAV_MODE)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
1421 if (_custom_mode == 0) {
1424 result = MAV_RESULT_ACCEPTED;
1425 }
else if (_custom_mode == 1) {
1428 result = MAV_RESULT_ACCEPTED;
1436 #if AP_AHRS_NAVEKF_AVAILABLE 1460 mavlink_msg_optical_flow_send(
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;
1490 uint8_t uid2[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN] = {0};
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);
1499 strncpy(flight_custom_version, version.
fw_hash_str,
sizeof(flight_custom_version) - 1);
1500 flight_custom_version[
sizeof(flight_custom_version) - 1] =
'\0';
1504 strncpy(middleware_custom_version, version.
middleware_hash_str,
sizeof(middleware_custom_version) - 1);
1505 middleware_custom_version[
sizeof(middleware_custom_version) - 1] =
'\0';
1509 strncpy(os_custom_version, version.
os_hash_str,
sizeof(os_custom_version) - 1);
1510 os_custom_version[
sizeof(os_custom_version) - 1] =
'\0';
1513 mavlink_msg_autopilot_version_send(
1517 middleware_sw_version,
1520 (uint8_t *)flight_custom_version,
1521 (uint8_t *)middleware_custom_version,
1522 (uint8_t *)os_custom_version,
1545 mavlink_msg_local_position_ned_send(
1565 mavlink_msg_vibration_send(
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);
1594 const float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};
1595 mavlink_msg_home_position_send(
1612 if (!
AP::ahrs().get_origin(ekf_origin)) {
1615 mavlink_msg_gps_global_origin_send(
1619 ekf_origin.
alt * 10,
1628 mavlink_msg_heartbeat_send(
1631 MAV_AUTOPILOT_ARDUPILOTMEGA,
1671 uint16_t values[16] {};
1673 for (uint8_t i=0; i<16; i++) {
1679 for (uint8_t i=0; i<16; i++) {
1680 if (values[i] == 65535) {
1684 mavlink_msg_servo_output_raw_send(
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]);
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(
1703 MAV_COLLISION_SRC_ADSB,
1719 mavlink_msg_command_long_send(
1723 MAV_CMD_ACCELCAL_VEHICLE_POS,
1734 if (airspeed !=
nullptr && airspeed->
healthy()) {
1763 mavlink_msg_vfr_hud_send(
1784 if (disable_overrides) {
1785 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 1787 int px4io_fd =
open(
"/dev/px4io", 0);
1788 if (px4io_fd >= 0) {
1791 if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_OK, 0) != 0) {
1794 if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 0) != 0) {
1808 bool hold_in_bootloader =
is_equal(packet.param1,3.0f);
1810 return MAV_RESULT_ACCEPTED;
1812 return MAV_RESULT_UNSUPPORTED;
1821 if (failsafe ==
nullptr) {
1822 return MAV_RESULT_UNSUPPORTED;
1825 bool should_terminate = packet.param1 > 0.5f;
1827 if (failsafe->
gcs_terminate(should_terminate,
"GCS request")) {
1828 return MAV_RESULT_ACCEPTED;
1830 return MAV_RESULT_FAILED;
1842 return MAV_RESULT_FAILED;
1844 return MAV_RESULT_ACCEPTED;
1870 mavlink_timesync_t tsync;
1871 mavlink_msg_timesync_decode(msg, &tsync);
1873 if (tsync.tc1 != 0) {
1883 "timesync response sysid=%u (latency=%fms)",
1885 round_trip_time_us*0.001f);
1888 if (df !=
nullptr) {
1906 mavlink_timesync_t rsync;
1908 rsync.ts1 = tsync.ts1;
1911 mavlink_msg_timesync_send(
1924 mavlink_msg_timesync_send(
1934 if (df ==
nullptr) {
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);
1953 memcpy(&text[offset], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
1968 if (camera ==
nullptr) {
1972 switch (msg->msgid) {
1973 case MAVLINK_MSG_ID_DIGICAM_CONFIGURE:
1976 case MAVLINK_MSG_ID_DIGICAM_CONTROL:
1987 if (camera ==
nullptr) {
1988 return MAV_RESULT_UNSUPPORTED;
1991 MAV_RESULT
result = MAV_RESULT_FAILED;
1992 switch (packet.command) {
1993 case MAV_CMD_DO_DIGICAM_CONFIGURE:
2001 result = MAV_RESULT_ACCEPTED;
2003 case MAV_CMD_DO_DIGICAM_CONTROL:
2004 camera->
control(packet.param1,
2010 result = MAV_RESULT_ACCEPTED;
2012 case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
2014 result = MAV_RESULT_ACCEPTED;
2017 result = MAV_RESULT_UNSUPPORTED;
2053 mavlink_set_gps_global_origin_t packet;
2054 mavlink_msg_set_gps_global_origin_decode(msg, &packet);
2057 if (!
check_latlng(packet.latitude, packet.longitude)) {
2074 #if HAL_RCINPUT_WITH_AP_RADIO 2076 mavlink_msg_data96_decode(msg, &m);
2082 if (radio !=
nullptr) {
2097 if (visual_odom ==
nullptr) {
2105 mavlink_vision_position_estimate_t m;
2106 mavlink_msg_vision_position_estimate_decode(msg, &m);
2114 mavlink_global_vision_position_estimate_t m;
2115 mavlink_msg_global_vision_position_estimate_decode(msg, &m);
2123 mavlink_vicon_position_estimate_t m;
2124 mavlink_msg_vicon_position_estimate_decode(msg, &m);
2140 const uint16_t payload_size)
2155 const float posErr = 0;
2156 const float angErr = 0;
2157 const uint32_t reset_timestamp_ms = 0;
2165 reset_timestamp_ms);
2179 "ssmmmrrr",
"FF000000",
"QQffffff",
2192 mavlink_att_pos_mocap_t m;
2193 mavlink_msg_att_pos_mocap_decode(msg, &m);
2203 const float posErr = 0;
2204 const float angErr = 0;
2205 const uint32_t timestamp_ms = m.time_usec * 0.001;
2206 const uint32_t reset_timestamp_ms = 0;
2214 reset_timestamp_ms);
2220 attitude.
to_euler(roll, pitch, yaw);
2228 if (accelcal !=
nullptr) {
2238 switch (msg->msgid) {
2239 case MAVLINK_MSG_ID_COMMAND_ACK: {
2244 case MAVLINK_MSG_ID_SETUP_SIGNING:
2248 case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
2250 case MAVLINK_MSG_ID_PARAM_SET:
2252 case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
2256 case MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN:
2260 case MAVLINK_MSG_ID_DEVICE_OP_READ:
2263 case MAVLINK_MSG_ID_DEVICE_OP_WRITE:
2266 case MAVLINK_MSG_ID_TIMESYNC:
2269 case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
2271 case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
2273 case MAVLINK_MSG_ID_LOG_ERASE:
2275 case MAVLINK_MSG_ID_LOG_REQUEST_END:
2277 case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
2282 case MAVLINK_MSG_ID_DIGICAM_CONFIGURE:
2284 case MAVLINK_MSG_ID_DIGICAM_CONTROL:
2288 case MAVLINK_MSG_ID_SET_MODE:
2292 case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
2296 case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
2298 case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
2300 case MAVLINK_MSG_ID_MISSION_COUNT:
2302 case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
2304 case MAVLINK_MSG_ID_MISSION_ITEM:
2306 case MAVLINK_MSG_ID_MISSION_ITEM_INT:
2308 case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
2310 case MAVLINK_MSG_ID_MISSION_REQUEST:
2312 case MAVLINK_MSG_ID_MISSION_ACK:
2314 case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
2318 case MAVLINK_MSG_ID_SERIAL_CONTROL:
2322 case MAVLINK_MSG_ID_GPS_RTCM_DATA:
2324 case MAVLINK_MSG_ID_GPS_INPUT:
2326 case MAVLINK_MSG_ID_HIL_GPS:
2328 case MAVLINK_MSG_ID_GPS_INJECT_DATA:
2332 case MAVLINK_MSG_ID_STATUSTEXT:
2336 case MAVLINK_MSG_ID_LED_CONTROL:
2341 case MAVLINK_MSG_ID_PLAY_TUNE:
2346 case MAVLINK_MSG_ID_RALLY_POINT:
2348 case MAVLINK_MSG_ID_RALLY_FETCH_POINT:
2352 case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
2356 case MAVLINK_MSG_ID_DATA96:
2360 case MAVLINK_MSG_ID_VISION_POSITION_DELTA:
2364 case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
2368 case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
2372 case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE:
2376 case MAVLINK_MSG_ID_ATT_POS_MOCAP:
2386 if (_mission ==
nullptr) {
2389 switch (msg->msgid) {
2390 case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
2397 case MAVLINK_MSG_ID_MISSION_ITEM:
2398 case MAVLINK_MSG_ID_MISSION_ITEM_INT:
2407 case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
2408 case MAVLINK_MSG_ID_MISSION_REQUEST:
2414 case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
2421 case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
2429 case MAVLINK_MSG_ID_MISSION_COUNT:
2435 case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
2441 case MAVLINK_MSG_ID_MISSION_ACK:
2459 send_text(MAV_SEVERITY_INFO,
"PX4: %s NuttX: %s",
2473 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 2475 if (sitl ==
nullptr) {
2485 if (compass ==
nullptr) {
2486 return MAV_RESULT_UNSUPPORTED;
2489 uint8_t compassNumber = -1;
2490 if (
is_equal(packet.param1, 2.0f)) {
2492 }
else if (
is_equal(packet.param1, 5.0f)) {
2494 }
else if (
is_equal(packet.param1, 6.0f)) {
2497 if (compassNumber == (uint8_t) -1) {
2498 return MAV_RESULT_FAILED;
2501 return MAV_RESULT_ACCEPTED;
2507 if (!
AP::ins().gyro_calibrated_ok_all()) {
2517 gcs().
send_text(MAV_SEVERITY_INFO,
"Updating barometer calibration");
2519 gcs().
send_text(MAV_SEVERITY_INFO,
"Barometer calibration complete");
2522 if (airspeed !=
nullptr) {
2526 return MAV_RESULT_ACCEPTED;
2531 if (
is_equal(packet.param1,1.0f)) {
2533 return MAV_RESULT_FAILED;
2535 return MAV_RESULT_ACCEPTED;
2538 if (
is_equal(packet.param3,1.0f)) {
2542 if (
is_equal(packet.param5,1.0f)) {
2545 return MAV_RESULT_FAILED;
2550 return MAV_RESULT_ACCEPTED;
2553 if (
is_equal(packet.param5,2.0f)) {
2555 return MAV_RESULT_FAILED;
2557 float trim_roll, trim_pitch;
2558 if (!
AP::ins().calibrate_trim(trim_roll, trim_pitch)) {
2559 return MAV_RESULT_FAILED;
2563 return MAV_RESULT_ACCEPTED;
2566 if (
is_equal(packet.param5,4.0f)) {
2571 return MAV_RESULT_UNSUPPORTED;
2578 return MAV_RESULT_FAILED;
2587 if (compass ==
nullptr) {
2588 return MAV_RESULT_UNSUPPORTED;
2595 if (!
is_equal(packet.param1,1.0f)) {
2596 return MAV_RESULT_FAILED;
2601 return MAV_RESULT_ACCEPTED;
2608 return MAV_RESULT_ACCEPTED;
2613 const MAV_MODE _base_mode = (MAV_MODE)packet.param1;
2614 const uint32_t _custom_mode = (uint32_t)packet.param2;
2622 return MAV_RESULT_FAILED;
2627 return MAV_RESULT_ACCEPTED;
2632 MAV_RESULT
result = MAV_RESULT_FAILED;
2634 switch (packet.command) {
2636 case MAV_CMD_DO_SET_MODE:
2640 case MAV_CMD_DO_SEND_BANNER:
2644 case MAV_CMD_DO_START_MAG_CAL:
2645 case MAV_CMD_DO_ACCEPT_MAG_CAL:
2646 case MAV_CMD_DO_CANCEL_MAG_CAL: {
2651 case MAV_CMD_START_RX_PAIR:
2655 case MAV_CMD_DO_DIGICAM_CONFIGURE:
2657 case MAV_CMD_DO_DIGICAM_CONTROL:
2659 case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
2663 case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
2668 case MAV_CMD_PREFLIGHT_CALIBRATION:
2672 case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: {
2677 case MAV_CMD_GET_HOME_POSITION:
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;
2689 case MAV_CMD_DO_SET_SERVO:
2691 case MAV_CMD_DO_REPEAT_SERVO:
2693 case MAV_CMD_DO_SET_RELAY:
2695 case MAV_CMD_DO_REPEAT_RELAY:
2699 case MAV_CMD_DO_FLIGHTTERMINATION:
2704 result = MAV_RESULT_UNSUPPORTED;
2714 if (compass ==
nullptr) {
2737 if (mission ==
nullptr) {
2767 mavlink_msg_hwstatus_send(
2813 if (camera ==
nullptr) {
2835 mavlink_msg_attitude_send(
2864 mavlink_msg_global_position_int_send(
3030 gcs().
send_text(MAV_SEVERITY_DEBUG,
"Sending unknown message (%u)",
id);
3031 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 3057 if (
gcs().out_of_time())
return;
3086 if (
gcs().out_of_time()) {
3107 const uint32_t max_lag_us = 500*1000UL;
3113 if (uart_receive_time != 0) {
3114 local_us = uart_receive_time;
3118 int64_t diff_us = int64_t(local_us) - int64_t(offboard_usec);
3127 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 3128 printf(
"link_offset_usec=%lld\n", (
long long int)diff_us);
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) {
3137 printf(
"msg from future %lld\n", (
long long int)(estimate_us - local_us));
3141 if (estimate_us + max_lag_us < int64_t(local_us)) {
3144 estimate_us = local_us - max_lag_us;
3146 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 3147 printf(
"offboard timestammp too old %lld\n", (
long long int)(local_us - estimate_us));
3164 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 3169 return estimate_us / 1000U;
uint16_t waypoint_dest_compid
void to_euler(float &roll, float &pitch, float &yaw) const
virtual uint32_t available_memory(void)
void handle_device_op_read(mavlink_message_t *msg)
virtual void send_banner()
int printf(const char *fmt,...)
bool get_soft_armed() const
virtual bool get_hagl(float &height) const
void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t *msg)
virtual bool get_velocity_NED(Vector3f &vec) const
static void handle_led_control(mavlink_message_t *msg)
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)
bool try_send_mission_message(enum ap_message id)
static AP_SerialManager serial_manager
AP_HAL::Util::perf_counter_t _perf_packet
virtual void send_scaled_pressure3()
static uint8_t get_valid_channel_count(void)
bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const
virtual void force_safety_no_wait(void)
virtual uint32_t telem_delay() const =0
uint8_t num_instances(void) const
void handle_send_autopilot_version(const mavlink_message_t *msg)
virtual uint32_t custom_mode() const =0
uint16_t voltage_mv() const
void handle_global_vision_position_estimate(mavlink_message_t *msg)
Vector3< float > Vector3f
#define PROXIMITY_SENSOR_ID_START
bool gcs_terminate(bool should_terminate, const char *reason)
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
void send_heartbeat(void) const
void set_ekf_origin(const Location &loc)
void update_calibration(void)
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)
virtual float board_voltage(void)=0
void handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const
static uint8_t chan_is_streaming
uint8_t num_deferred_messages
virtual void force_safety_off(void)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
bool stream_trigger(enum streams stream_num)
void send_autopilot_version() const
enum Rotation orientation() const
virtual const Vector3f & get_gyro(void) const =0
uint8_t activeCores(void) const
virtual uint16_t read(uint8_t ch)=0
MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet)
uint16_t distance_cm() const
SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const
void handle_timesync(mavlink_message_t *msg)
AP_HAL::UARTDriver * console
virtual void begin(uint32_t baud)=0
void send_vibration() const
virtual void handleMessage(mavlink_message_t *msg)=0
uint32_t last_heartbeat_time
AP_Param * _queued_parameter
next parameter to
void control_msg(const mavlink_message_t *msg)
decode deprecated MavLink message that controls camera.
const Vector3f & get_gyro(uint8_t i) const
float get_temperature(void) const
#define RANGEFINDER_MAX_INSTANCES
bool get_upward_distance(uint8_t instance, float &distance) const
virtual bool get_position(struct Location &loc) const =0
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
virtual bool get_relative_position_NED_home(Vector3f &vec) const
static uint32_t reserve_param_space_start_ms
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.
MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet)
uint16_t get_current_nav_index() const
static const struct stream_entries all_stream_entries[]
void handle_device_op_write(mavlink_message_t *msg)
bool handle_mission_item(mavlink_message_t *msg, AP_Mission &mission)
struct GCS_MAVLINK::@196 alternative
static RangeFinder * get_singleton(void)
const struct Location & get_home(void) const
void truncate(uint16_t index)
truncate - truncate any mission items beyond given index
void send_mavlink_gps2_raw(mavlink_channel_t chan)
float get_airspeed(uint8_t i) const
bool send_battery_status() const
uint16_t num_commands() const
static AP_Frsky_Telem * frsky_telemetry_p
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)
uint32_t correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size)
void getEulerAngles(int8_t instance, Vector3f &eulers) const
#define PROXIMITY_MAX_DIRECTION
AP_HAL::UARTDriver * mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS]
MAVLink stream used for uartA.
void set_capabilities(uint64_t cap)
void handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg)
virtual void reset_gyro_drift(void)=0
float adjust_rate_for_stream_trigger(enum streams stream_num)
static int comm_get_txspace(mavlink_channel_t chan)
void service_statustext(void)
void from_euler(float roll, float pitch, float yaw)
MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides)
void handle_common_param_message(mavlink_message_t *msg)
void handle_msg(mavlink_message_t *msg)
void handle_vision_position_delta(mavlink_message_t *msg)
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd)=0
void handle_mission_write_partial_list(AP_Mission &mission, mavlink_message_t *msg)
uint64_t timesync_receive_timestamp_ns() const
void handle_request_data_stream(mavlink_message_t *msg)
static bool receiver_bind(const int dsmMode)
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet)
void Log_Write_Radio(const mavlink_radio_t &packet)
bool add_cmd(Mission_Command &cmd)
void Log_Write_Home_And_Origin()
virtual bool usb_connected(void)=0
const Mission_Command & get_current_nav_cmd() const
get_current_nav_cmd - returns the current "navigation" command
virtual const AP_FWVersion & get_fwver() const =0
void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
virtual class AP_Camera * get_camera() const =0
static uint8_t active_channel_mask(void)
const char * middleware_hash_str
static AP_Notify * instance(void)
float distance_max() const
uint16_t cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]
mavlink_channel_t get_chan() const
int32_t lat
param 3 - Latitude * 10**7
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
void handle_att_pos_mocap(mavlink_message_t *msg)
struct GCS_MAVLINK::@197 lag_correction
void handle_statustext(mavlink_message_t *msg)
virtual uint16_t power_status_flags(void)
void send_rangefinder_downward() const
virtual MAV_STATE system_status() const =0
void handle_common_vision_position_estimate_data(const uint64_t usec, const float x, const float y, const float z, const float roll, const float pitch, const float yaw, const uint16_t payload_size)
virtual bool have_inertial_nav(void) const
bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const
void send_servo_output_raw()
const Vector2f & flowRate() const
uint16_t waypoint_request_last
static AP_InertialSensor ins
bool replace_cmd(uint16_t index, Mission_Command &cmd)
const Vector3f & get_accel(uint8_t i) const
uint8_t num_sensors(void) const
float consumed_wh(uint8_t instance) const
consumed_wh - returns total energy drawn since start-up in watt.hours
AP_HAL::Util::perf_counter_t _perf_update
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet)
static const AP_SerialManager * serialmanager_p
static bool mission_cmd_to_mavlink(const AP_Mission::Mission_Command &cmd, mavlink_mission_item_t &packet)
static AP_Radio * instance(void)
virtual void delay(uint16_t ms)=0
virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet)
static bool valid_channel(mavlink_channel_t chan)
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd)=0
static MAV_MISSION_RESULT mavlink_to_mission_cmd(const mavlink_mission_item_t &packet, AP_Mission::Mission_Command &cmd)
bool telemetry_delayed() const
void send_message(enum ap_message id)
void send_mag_cal_report(mavlink_channel_t chan)
#define HAVE_PAYLOAD_SPACE(chan, id)
Proximity_Type get_type(uint8_t instance) const
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
virtual bool set_mode(uint8_t mode)=0
void send_mavlink_gps_raw(mavlink_channel_t chan)
virtual MAV_TYPE frame_type() const =0
void handle_common_message(mavlink_message_t *msg)
static SRV_Channel * srv_channel(uint8_t i)
virtual void printf(const char *,...) FMT_PRINTF(2
void queued_waypoint_send()
Send the next pending waypoint, called from deferred message handling code.
void send_queued_parameters(void)
virtual void set_trim(Vector3f new_trim)
bool try_send_gps_message(enum ap_message id)
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio)
static uint16_t comm_get_available(mavlink_channel_t chan)
const ap_message * ap_message_ids
virtual AP_VisualOdom * get_visual_odom() const
virtual void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg)
bool send_proximity() const
void handle_mission_count(AP_Mission &mission, mavlink_message_t *msg)
MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
static MAVLink_routing routing
const uint8_t num_ap_message_ids
virtual float vfr_hud_airspeed() const
float ground_speed(uint8_t instance) const
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
void Log_Write(const char *name, const char *labels, const char *fmt,...)
virtual void send_attitude() const
bool try_send_compass_message(enum ap_message id)
const uint16_t waypoint_receive_timeout
virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
uint16_t waypoint_dest_sysid
void handle_vicon_position_estimate(mavlink_message_t *msg)
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet)
static void erase_all(void)
Proximity_Status get_status(uint8_t instance) const
float get_ground_pressure(void) const
virtual uint8_t sysid_my_gcs() const =0
static OpticalFlow optflow
bool check_and_forward(mavlink_channel_t in_channel, const mavlink_message_t *msg)
bool has_current(uint8_t instance) const
has_current - returns true if battery monitor instance provides current info
void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
const NavEKF2 & get_NavEKF2_const(void) const
virtual size_t write(uint8_t)=0
void queue_message(MAV_SEVERITY severity, const char *text)
void send_local_position() const
float time_to_closest_approach
const Vector3f & get_offsets(uint8_t i) const
virtual int32_t global_position_int_relative_alt() const
int close(int fileno)
POSIX Close a file with fileno handel.
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)
void handleMessage(const mavlink_message_t *msg)
void set_out_of_time(bool val)
mavlink_system_t mavlink_system
MAVLink system definition.
virtual void send_position_target_global_int()
virtual void perf_end(perf_counter_t h)
uint16_t mission_item_reached_index
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet)
static DataFlash_Class * instance(void)
MAV_RESULT handle_servorelay_message(mavlink_command_long_t &packet)
void setup_uart(const AP_SerialManager &serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance)
FIRMWARE_VERSION_TYPE fw_type
void handle_common_mission_message(mavlink_message_t *msg)
virtual const Vector3f & get_gyro_drift(void) const =0
virtual float servorail_voltage(void)
void calibrate(bool in_startup)
bool check_latlng(float lat, float lng)
static uint32_t last_radio_status_remrssi_ms
struct Location global_position_current_loc
void send_ekf_origin() const
virtual MAV_RESULT _handle_command_preflight_calibration_baro()
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet)
bool set_current_cmd(uint16_t index)
void send_power_status(void)
virtual void set_flow_control(enum flow_control flow_control_setting)
uint32_t get_accel_clip_count(uint8_t instance) const
void handle_data_packet(mavlink_message_t *msg)
float current_amps(uint8_t instance) const
current_amps - returns the instantaneous current draw in amperes
virtual bool get_system_id(char buf[40])
void log_vision_position_estimate_data(const uint64_t usec, const float x, const float y, const float z, const float roll, const float pitch, const float yaw)
virtual float get_error_rp(void) const =0
virtual bool force_safety_on(void)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void handle_mission_clear_all(AP_Mission &mission, mavlink_message_t *msg)
float get_pressure(void) const
void simstate_send(mavlink_channel_t chan)
void send_feedback(mavlink_channel_t chan)
const Vector2f & bodyRate() const
void handle_serial_control(const mavlink_message_t *msg)
virtual int16_t vfr_hud_throttle() const
void push_deferred_messages()
void queued_param_send()
Send the next pending parameter, called from deferred message handling code.
MAV_RESULT simple_accel_cal()
static void handle_play_tune(mavlink_message_t *msg)
float get_differential_pressure(uint8_t i) const
void handle_common_camera_message(const mavlink_message_t *msg)
virtual void send_simstate() const
static AP_Proximity * get_singleton(void)
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg)
void send_named_float(const char *name, float value) const
AP_BattMonitor & battery()
static AP_Airspeed * get_singleton()
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
uint32_t waypoint_timelast_receive
uint16_t num_commands_max() const
num_commands_max - returns maximum number of commands that can be stored
uint8_t get_count(void) const
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet)
uint8_t orientation[PROXIMITY_MAX_DIRECTION]
#define PAYLOAD_SIZE(chan, id)
void handle_setup_signing(const mavlink_message_t *msg)
virtual MAV_MODE base_mode() const =0
static const struct AP_Param::GroupInfo var_info[]
virtual void reboot(bool hold_in_bootloader)=0
virtual int32_t global_position_int_alt() const
Catch-all header that defines all supported optical flow classes.
float distance[PROXIMITY_MAX_DIRECTION]
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const
int32_t lng
param 4 - Longitude * 10**7
static const uint8_t num_gcs
AP_HAL::UARTDriver * _port
The stream we are communicating over.
void set_trigger_distance(uint32_t distance_m)
virtual uint64_t receive_time_constraint_us(uint16_t nbytes)
char _perf_update_name[16]
uint16_t get_output_pwm(void) const
MAV_COLLISION_THREAT_LEVEL threat_level
virtual bool vfr_hud_make_alt_relative() const
int snprintf(char *str, size_t size, const char *format,...)
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)
virtual void perf_begin(perf_counter_t h)
virtual enum flow_control get_flow_control(void)
float closest_approach_xy
MAV_RESULT _set_mode_common(const MAV_MODE base_mode, const uint32_t custom_mode)
enum ap_message deferred_messages[MSG_LAST]
void handle_msg(const mavlink_message_t *msg)
static uint8_t streaming_channel_mask(void)
void handle_mission_request(AP_Mission &mission, mavlink_message_t *msg)
void load_signing_key(void)
static class GCS * instance()
static MAV_MISSION_RESULT mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t &packet, AP_Mission::Mission_Command &cmd)
uint8_t next_deferred_message
virtual AP_Mission * get_mission()=0
uint64_t get_capabilities() const
static void save_signing_timestamp(bool force_save_now)
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet)
AP_AccelCal * get_acal() const
int snprintf(char *str, size_t size, const char *fmt,...)
static uint16_t get_radio_in(const uint8_t chan)
bool gcs_alternative_active[MAVLINK_COMM_NUM_BUFFERS]
virtual bool get_origin(Location &ret) const
void handle_set_mode(mavlink_message_t *msg)
virtual bool get_secondary_attitude(Vector3f &eulers) const
const Vector3f & get_accel_offsets(uint8_t i) const
void send_sensor_offsets()
uint8_t get_gyro_count(void) const
void Log_Write_EntireMission(const AP_Mission &mission)
bool get_temperature(float &temperature) const
void send_mag_cal_progress(mavlink_channel_t chan)
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour)
AP_InertialSensor & ins()
virtual AP_AdvancedFailsafe * get_advanced_failsafe() const
void handle_set_gps_global_origin(const mavlink_message_t *msg)
void send_text(const char *str)
virtual void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg)
uint32_t waypoint_timelast_request
int16_t min_distance_cm() const
float distance_min() const
void send_scaled_pressure()
char _perf_packet_name[16]
void send_global_position_int()
void send_message(enum ap_message id)
void panic(const char *errormsg,...) FMT_PRINTF(1
virtual void handle_command_ack(const mavlink_message_t *msg)
bool has_consumed_energy(uint8_t instance) const
has_consumed_energy - returns true if battery monitor instance provides consumed energy info ...
virtual MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet)
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
uint8_t num_instances(void) const
virtual bool in_hil_mode() 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
void send_accelcal_vehicle_position(uint32_t position)
Vector3f get_vibration_levels() const
bool healthy(uint8_t i) const
void handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
virtual bool try_send_message(enum ap_message id)
void start(GCS_MAVLINK *gcs)
void update(uint32_t max_time_us=1000)
void handle_common_rally_message(mavlink_message_t *msg)
static uint8_t mavlink_active
virtual void get_relative_position_D_home(float &posD) const =0
virtual bool set_origin(const Location &loc)
bool getLLH(struct Location &loc) const
uint16_t waypoint_request_i
bool try_send_camera_message(enum ap_message id)
virtual Compass * get_compass() const =0
void handle_vision_position_estimate(mavlink_message_t *msg)
virtual bool in_delay_callback() const
AP_HAL::Scheduler * scheduler
uint64_t timesync_timestamp_ns() const
bool send_distance_sensor() const
#define MAVLINK_COMM_NUM_BUFFERS
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
virtual float vfr_hud_climbrate() const
const cells & get_cell_voltages() const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
AP_HAL::AnalogIn * analogin
virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
struct GCS_MAVLINK::@195 _timesync_request
void handle_common_gps_message(mavlink_message_t *msg)