2013-12-15 03:57:15 -04:00
|
|
|
/*
|
|
|
|
Common GCS MAVLink functions for all vehicle types
|
|
|
|
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-11-24 05:37:37 -04:00
|
|
|
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_Vehicle/AP_Vehicle.h>
|
2017-08-08 03:24:21 -03:00
|
|
|
#include <AP_RangeFinder/RangeFinder_Backend.h>
|
2013-12-15 03:57:15 -04:00
|
|
|
|
2016-05-05 19:18:36 -03:00
|
|
|
#include "GCS.h"
|
|
|
|
|
2017-08-02 06:23:07 -03:00
|
|
|
#include <stdio.h>
|
2016-08-11 00:17:32 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
|
|
#include <drivers/drv_pwm_output.h>
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#endif
|
|
|
|
|
2018-01-18 02:32:22 -04:00
|
|
|
#ifdef HAL_RCINPUT_WITH_AP_RADIO
|
|
|
|
#include <AP_Radio/AP_Radio.h>
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
|
|
|
#endif
|
|
|
|
|
2013-12-16 20:56:49 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2014-03-18 18:44:58 -03:00
|
|
|
uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms;
|
2014-07-17 08:03:12 -03:00
|
|
|
uint8_t GCS_MAVLINK::mavlink_active = 0;
|
2016-06-13 17:36:34 -03:00
|
|
|
uint8_t GCS_MAVLINK::chan_is_streaming = 0;
|
2016-05-27 21:41:52 -03:00
|
|
|
uint32_t GCS_MAVLINK::reserve_param_space_start_ms;
|
2014-03-18 18:44:58 -03:00
|
|
|
|
2016-05-30 07:05:00 -03:00
|
|
|
GCS *GCS::_singleton = nullptr;
|
|
|
|
|
2016-01-20 02:20:30 -04:00
|
|
|
GCS_MAVLINK::GCS_MAVLINK()
|
2013-12-15 03:57:15 -04:00
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
2013-12-16 20:56:49 -04:00
|
|
|
|
|
|
|
void
|
2015-01-23 09:45:14 -04:00
|
|
|
GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
|
2013-12-16 20:56:49 -04:00
|
|
|
{
|
2016-03-28 11:33:59 -03:00
|
|
|
if (!valid_channel(mav_chan)) {
|
2015-05-15 02:40:23 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-12-09 23:39:32 -04:00
|
|
|
_port = port;
|
2015-01-23 09:45:14 -04:00
|
|
|
chan = mav_chan;
|
|
|
|
|
2015-05-15 02:40:23 -03:00
|
|
|
mavlink_comm_port[chan] = _port;
|
|
|
|
initialised = true;
|
2016-10-30 02:24:21 -03:00
|
|
|
_queued_parameter = nullptr;
|
2017-04-28 01:35:53 -03:00
|
|
|
|
2017-09-12 14:24:13 -03:00
|
|
|
snprintf(_perf_packet_name, sizeof(_perf_packet_name), "GCS_Packet_%u", chan);
|
|
|
|
_perf_packet = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_packet_name);
|
2017-08-02 06:23:07 -03:00
|
|
|
|
2017-09-12 14:24:13 -03:00
|
|
|
snprintf(_perf_update_name, sizeof(_perf_update_name), "GCS_Update_%u", chan);
|
|
|
|
_perf_update = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_update_name);
|
2013-12-16 20:56:49 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2014-05-15 22:44:33 -03:00
|
|
|
/*
|
|
|
|
setup a UART, handling begin() and init()
|
|
|
|
*/
|
|
|
|
void
|
2015-03-27 22:47:29 -03:00
|
|
|
GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance)
|
2014-05-15 22:44:33 -03:00
|
|
|
{
|
2016-05-16 01:05:09 -03:00
|
|
|
serialmanager_p = &serial_manager;
|
2015-01-29 00:36:19 -04:00
|
|
|
|
2016-05-16 01:05:09 -03:00
|
|
|
// search for serial port
|
|
|
|
|
2015-01-29 00:36:19 -04:00
|
|
|
AP_HAL::UARTDriver *uart;
|
2015-03-27 22:47:29 -03:00
|
|
|
uart = serial_manager.find_serial(protocol, instance);
|
2016-10-30 02:24:21 -03:00
|
|
|
if (uart == nullptr) {
|
2015-01-19 09:33:31 -04:00
|
|
|
// return immediately if not found
|
2014-05-15 22:44:33 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-01-23 09:45:14 -04:00
|
|
|
// get associated mavlink channel
|
|
|
|
mavlink_channel_t mav_chan;
|
2015-03-27 22:47:29 -03:00
|
|
|
if (!serial_manager.get_mavlink_channel(protocol, instance, mav_chan)) {
|
2015-01-23 09:45:14 -04:00
|
|
|
// return immediately in unlikely case mavlink channel cannot be found
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-05-15 22:44:33 -03:00
|
|
|
/*
|
|
|
|
Now try to cope with SiK radios that may be stuck in bootloader
|
|
|
|
mode because CTS was held while powering on. This tells the
|
|
|
|
bootloader to wait for a firmware. It affects any SiK radio with
|
|
|
|
CTS connected that is externally powered. To cope we send 0x30
|
|
|
|
0x20 at 115200 on startup, which tells the bootloader to reset
|
|
|
|
and boot normally
|
|
|
|
*/
|
2015-01-29 00:36:19 -04:00
|
|
|
uart->begin(115200);
|
|
|
|
AP_HAL::UARTDriver::flow_control old_flow_control = uart->get_flow_control();
|
|
|
|
uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
2014-05-15 22:44:33 -03:00
|
|
|
for (uint8_t i=0; i<3; i++) {
|
|
|
|
hal.scheduler->delay(1);
|
2015-01-29 00:36:19 -04:00
|
|
|
uart->write(0x30);
|
|
|
|
uart->write(0x20);
|
2014-05-15 22:44:33 -03:00
|
|
|
}
|
2015-07-13 20:44:31 -03:00
|
|
|
// since tcdrain() and TCSADRAIN may not be implemented...
|
|
|
|
hal.scheduler->delay(1);
|
|
|
|
|
2015-01-29 00:36:19 -04:00
|
|
|
uart->set_flow_control(old_flow_control);
|
2014-05-15 22:44:33 -03:00
|
|
|
|
2015-01-19 09:33:31 -04:00
|
|
|
// now change back to desired baudrate
|
2015-04-06 18:47:51 -03:00
|
|
|
uart->begin(serial_manager.find_baudrate(protocol, instance));
|
2014-05-15 22:44:33 -03:00
|
|
|
|
|
|
|
// and init the gcs instance
|
2015-01-29 00:36:19 -04:00
|
|
|
init(uart, mav_chan);
|
2016-01-20 22:49:06 -04:00
|
|
|
|
2016-05-16 01:05:09 -03:00
|
|
|
AP_SerialManager::SerialProtocol mavlink_protocol = serialmanager_p->get_mavlink_protocol(mav_chan);
|
2016-01-21 23:41:11 -04:00
|
|
|
mavlink_status_t *status = mavlink_get_channel_status(chan);
|
2016-05-16 01:05:09 -03:00
|
|
|
if (status == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2) {
|
|
|
|
// load signing key
|
|
|
|
load_signing_key();
|
|
|
|
|
2016-10-30 02:24:21 -03:00
|
|
|
if (status->signing == nullptr) {
|
2016-05-16 01:05:09 -03:00
|
|
|
// if signing is off start by sending MAVLink1.
|
|
|
|
status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
|
|
|
}
|
2016-09-15 20:47:55 -03:00
|
|
|
// announce that we are MAVLink2 capable
|
|
|
|
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MAVLINK2);
|
2016-05-16 01:05:09 -03:00
|
|
|
} else if (status) {
|
|
|
|
// user has asked to only send MAVLink1
|
|
|
|
status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (chan == MAVLINK_COMM_0) {
|
2016-04-05 01:09:47 -03:00
|
|
|
// Always start with MAVLink1 on first port for now, to allow for recovery
|
|
|
|
// after experiments with MAVLink2
|
2016-01-21 23:41:11 -04:00
|
|
|
status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
2016-05-16 01:05:09 -03:00
|
|
|
}
|
2014-05-15 22:44:33 -03:00
|
|
|
}
|
|
|
|
|
2013-12-16 20:56:49 -04:00
|
|
|
|
|
|
|
/**
|
|
|
|
* @brief Send the next pending waypoint, called from deferred message
|
|
|
|
* handling code
|
|
|
|
*/
|
|
|
|
void
|
|
|
|
GCS_MAVLINK::queued_waypoint_send()
|
|
|
|
{
|
|
|
|
if (initialised &&
|
|
|
|
waypoint_receiving &&
|
|
|
|
waypoint_request_i <= waypoint_request_last) {
|
|
|
|
mavlink_msg_mission_request_send(
|
|
|
|
chan,
|
|
|
|
waypoint_dest_sysid,
|
|
|
|
waypoint_dest_compid,
|
2017-04-11 08:41:45 -03:00
|
|
|
waypoint_request_i,
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2013-12-16 20:56:49 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-12-28 01:00:19 -04:00
|
|
|
void GCS_MAVLINK::send_meminfo(void)
|
|
|
|
{
|
|
|
|
unsigned __brkval = 0;
|
2015-11-05 01:06:34 -04:00
|
|
|
uint32_t memory = hal.util->available_memory();
|
2016-05-16 03:41:17 -03:00
|
|
|
mavlink_msg_meminfo_send(chan, __brkval, memory & 0xFFFF, memory);
|
2013-12-28 01:00:19 -04:00
|
|
|
}
|
|
|
|
|
2014-02-13 07:07:13 -04:00
|
|
|
// report power supply status
|
|
|
|
void GCS_MAVLINK::send_power_status(void)
|
|
|
|
{
|
|
|
|
mavlink_msg_power_status_send(chan,
|
|
|
|
hal.analogin->board_voltage() * 1000,
|
|
|
|
hal.analogin->servorail_voltage() * 1000,
|
|
|
|
hal.analogin->power_status_flags());
|
|
|
|
}
|
2014-01-03 20:30:32 -04:00
|
|
|
|
2017-04-07 17:13:35 -03:00
|
|
|
void GCS_MAVLINK::send_battery_status(const AP_BattMonitor &battery, const uint8_t instance) const
|
|
|
|
{
|
2017-04-08 00:28:14 -03:00
|
|
|
// catch the battery backend not supporting the required number of cells
|
|
|
|
static_assert(sizeof(AP_BattMonitor::cells) >= (sizeof(uint16_t) * MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN),
|
|
|
|
"Not enough battery cells for the MAVLink message");
|
|
|
|
|
2017-04-08 05:25:59 -03:00
|
|
|
float temp;
|
|
|
|
bool got_temperature = battery.get_temperature(temp, instance);
|
2017-04-07 17:13:35 -03:00
|
|
|
mavlink_msg_battery_status_send(chan,
|
|
|
|
instance, // id
|
|
|
|
MAV_BATTERY_FUNCTION_UNKNOWN, // function
|
|
|
|
MAV_BATTERY_TYPE_UNKNOWN, // type
|
2017-04-08 05:25:59 -03:00
|
|
|
got_temperature ? ((int16_t) (temp * 100)) : INT16_MAX, // temperature. INT16_MAX if unknown
|
2017-04-08 00:28:14 -03:00
|
|
|
battery.get_cell_voltages(instance).cells, // cell voltages
|
2017-04-07 17:13:35 -03:00
|
|
|
battery.has_current(instance) ? battery.current_amps(instance) * 100 : -1, // current
|
|
|
|
battery.has_current(instance) ? battery.current_total_mah(instance) : -1, // total current
|
2018-01-10 04:12:47 -04:00
|
|
|
battery.has_consumed_energy(instance) ? battery.consumed_wh(instance) * 36 : -1, // consumed energy in hJ (hecto-Joules)
|
2017-04-07 17:13:35 -03:00
|
|
|
battery.capacity_remaining_pct(instance));
|
|
|
|
}
|
|
|
|
|
|
|
|
// returns true if all battery instances were reported
|
|
|
|
bool GCS_MAVLINK::send_battery_status(const AP_BattMonitor &battery) const
|
|
|
|
{
|
|
|
|
for(uint8_t i = 0; i < battery.num_instances(); i++) {
|
|
|
|
CHECK_PAYLOAD_SIZE(BATTERY_STATUS);
|
|
|
|
send_battery_status(battery, i);
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-08-08 03:24:21 -03:00
|
|
|
void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor) const
|
2017-05-29 14:03:43 -03:00
|
|
|
{
|
2017-08-08 03:24:21 -03:00
|
|
|
if (sensor == nullptr) {
|
|
|
|
// should not happen
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (!sensor->has_data()) {
|
|
|
|
return;
|
2017-05-29 14:03:43 -03:00
|
|
|
}
|
2017-08-08 03:24:21 -03:00
|
|
|
|
|
|
|
mavlink_msg_distance_sensor_send(
|
|
|
|
chan,
|
2017-08-08 04:25:09 -03:00
|
|
|
AP_HAL::millis(), // time since system boot TODO: take time of measurement
|
|
|
|
sensor->min_distance_cm(), // minimum distance the sensor can measure in centimeters
|
|
|
|
sensor->max_distance_cm(), // maximum distance the sensor can measure in centimeters
|
|
|
|
sensor->distance_cm(), // current distance reading
|
|
|
|
sensor->get_mav_distance_sensor_type(), // type from MAV_DISTANCE_SENSOR enum
|
|
|
|
sensor->instance(), // onboard ID of the sensor == instance
|
|
|
|
sensor->orientation(), // direction the sensor faces from MAV_SENSOR_ORIENTATION enum
|
|
|
|
0); // Measurement covariance in centimeters, 0 for unknown / invalid readings
|
2017-05-29 14:03:43 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool GCS_MAVLINK::send_distance_sensor(const RangeFinder &rangefinder) const
|
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
|
|
|
|
CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
|
2017-08-08 03:24:21 -03:00
|
|
|
AP_RangeFinder_Backend *sensor = rangefinder.get_backend(i);
|
|
|
|
if (sensor == nullptr) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
send_distance_sensor(sensor);
|
2017-05-29 14:03:43 -03:00
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-05-30 07:33:03 -03:00
|
|
|
void GCS_MAVLINK::send_distance_sensor_downward(const RangeFinder &rangefinder) const
|
|
|
|
{
|
2017-08-08 03:24:21 -03:00
|
|
|
AP_RangeFinder_Backend *s = rangefinder.find_instance(ROTATION_PITCH_270);
|
|
|
|
if (s == nullptr) {
|
2017-05-30 07:33:03 -03:00
|
|
|
return;
|
|
|
|
}
|
2017-08-08 03:24:21 -03:00
|
|
|
send_distance_sensor(s);
|
2017-05-30 07:33:03 -03:00
|
|
|
}
|
|
|
|
|
2017-06-05 15:49:34 -03:00
|
|
|
void GCS_MAVLINK::send_rangefinder_downward(const RangeFinder &rangefinder) const
|
2017-05-30 07:33:37 -03:00
|
|
|
{
|
2017-08-08 03:24:21 -03:00
|
|
|
AP_RangeFinder_Backend *s = rangefinder.find_instance(ROTATION_PITCH_270);
|
|
|
|
if (s == nullptr) {
|
2017-05-30 07:33:37 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
mavlink_msg_rangefinder_send(
|
|
|
|
chan,
|
2017-08-08 03:24:21 -03:00
|
|
|
s->distance_cm() * 0.01f,
|
|
|
|
s->voltage_mv() * 0.001f);
|
2017-05-30 07:33:37 -03:00
|
|
|
}
|
|
|
|
|
2017-07-14 14:00:18 -03:00
|
|
|
bool GCS_MAVLINK::send_proximity(const AP_Proximity &proximity) const
|
2017-07-14 14:00:01 -03:00
|
|
|
{
|
|
|
|
// return immediately if no proximity sensor is present
|
|
|
|
if (proximity.get_status() == AP_Proximity::Proximity_NotConnected) {
|
2017-07-14 14:00:18 -03:00
|
|
|
return false;
|
2017-07-14 14:00:01 -03:00
|
|
|
}
|
|
|
|
// send horizontal distances
|
|
|
|
AP_Proximity::Proximity_Distance_Array dist_array;
|
|
|
|
if (proximity.get_horizontal_distances(dist_array)) {
|
2017-07-14 14:00:18 -03:00
|
|
|
for (uint8_t i = 0; i < PROXIMITY_MAX_DIRECTION; i++) {
|
|
|
|
CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
|
2017-07-14 14:00:01 -03:00
|
|
|
mavlink_msg_distance_sensor_send(
|
|
|
|
chan,
|
|
|
|
AP_HAL::millis(), // time since system boot
|
|
|
|
(uint16_t)(proximity.distance_min() * 100.0f), // minimum distance the sensor can measure in centimeters
|
|
|
|
(uint16_t)(proximity.distance_max() * 100.0f), // maximum distance the sensor can measure in centimeters
|
|
|
|
(uint16_t)(dist_array.distance[i] * 100.0f), // current distance reading
|
|
|
|
MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum
|
|
|
|
PROXIMITY_SENSOR_ID_START + i, // onboard ID of the sensor
|
|
|
|
dist_array.orientation[i], // direction the sensor faces from MAV_SENSOR_ORIENTATION enum
|
|
|
|
0); // Measurement covariance in centimeters, 0 for unknown / invalid readings
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// send upward distance
|
|
|
|
float dist_up;
|
2017-07-14 14:00:18 -03:00
|
|
|
if (proximity.get_upward_distance(dist_up)) {
|
|
|
|
CHECK_PAYLOAD_SIZE(DISTANCE_SENSOR);
|
2017-07-14 14:00:01 -03:00
|
|
|
mavlink_msg_distance_sensor_send(
|
|
|
|
chan,
|
|
|
|
AP_HAL::millis(), // time since system boot
|
|
|
|
(uint16_t)(proximity.distance_min() * 100.0f), // minimum distance the sensor can measure in centimeters
|
|
|
|
(uint16_t)(proximity.distance_max() * 100.0f), // maximum distance the sensor can measure in centimeters
|
|
|
|
(uint16_t)(dist_up * 100.0f), // current distance reading
|
|
|
|
MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum
|
|
|
|
PROXIMITY_SENSOR_ID_START + PROXIMITY_MAX_DIRECTION + 1, // onboard ID of the sensor
|
|
|
|
MAV_SENSOR_ROTATION_PITCH_90, // direction upwards
|
|
|
|
0); // Measurement covariance in centimeters, 0 for unknown / invalid readings
|
|
|
|
}
|
2017-07-14 14:00:18 -03:00
|
|
|
return true;
|
2017-07-14 14:00:01 -03:00
|
|
|
}
|
|
|
|
|
2014-01-03 20:30:32 -04:00
|
|
|
// report AHRS2 state
|
|
|
|
void GCS_MAVLINK::send_ahrs2(AP_AHRS &ahrs)
|
|
|
|
{
|
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
|
|
Vector3f euler;
|
2015-07-13 03:07:40 -03:00
|
|
|
struct Location loc {};
|
|
|
|
if (ahrs.get_secondary_attitude(euler)) {
|
2014-01-03 20:30:32 -04:00
|
|
|
mavlink_msg_ahrs2_send(chan,
|
|
|
|
euler.x,
|
|
|
|
euler.y,
|
|
|
|
euler.z,
|
|
|
|
loc.alt*1.0e-2f,
|
|
|
|
loc.lat,
|
|
|
|
loc.lng);
|
|
|
|
}
|
2015-09-22 23:22:54 -03:00
|
|
|
AP_AHRS_NavEKF &_ahrs = reinterpret_cast<AP_AHRS_NavEKF&>(ahrs);
|
2016-05-23 09:02:12 -03:00
|
|
|
if (_ahrs.get_NavEKF2().activeCores() > 0 &&
|
|
|
|
HAVE_PAYLOAD_SPACE(chan, AHRS3)) {
|
2015-09-22 23:22:54 -03:00
|
|
|
_ahrs.get_NavEKF2().getLLH(loc);
|
2015-11-07 07:55:08 -04:00
|
|
|
_ahrs.get_NavEKF2().getEulerAngles(-1,euler);
|
2015-09-22 23:22:54 -03:00
|
|
|
mavlink_msg_ahrs3_send(chan,
|
|
|
|
euler.x,
|
|
|
|
euler.y,
|
|
|
|
euler.z,
|
|
|
|
loc.alt*1.0e-2f,
|
|
|
|
loc.lat,
|
|
|
|
loc.lng,
|
|
|
|
0, 0, 0, 0);
|
|
|
|
}
|
2014-01-03 20:30:32 -04:00
|
|
|
#endif
|
|
|
|
}
|
2014-03-17 23:52:07 -03:00
|
|
|
|
2014-03-18 10:30:59 -03:00
|
|
|
/*
|
|
|
|
handle a MISSION_REQUEST_LIST mavlink packet
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_mission_request_list_t packet;
|
|
|
|
mavlink_msg_mission_request_list_decode(msg, &packet);
|
|
|
|
|
|
|
|
// reply with number of commands in the mission. The GCS will then request each command separately
|
2017-04-11 08:41:45 -03:00
|
|
|
mavlink_msg_mission_count_send(chan,msg->sysid, msg->compid, mission.num_commands(),
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2014-03-18 10:30:59 -03:00
|
|
|
|
|
|
|
// set variables to help handle the expected sending of commands to the GCS
|
|
|
|
waypoint_receiving = false; // record that we are sending commands (i.e. not receiving)
|
|
|
|
}
|
2014-03-17 23:52:07 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
handle a MISSION_REQUEST mavlink packet
|
|
|
|
*/
|
2014-03-18 19:59:40 -03:00
|
|
|
void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t *msg)
|
2014-03-17 23:52:07 -03:00
|
|
|
{
|
2014-03-18 19:59:40 -03:00
|
|
|
AP_Mission::Mission_Command cmd;
|
2014-03-18 10:30:59 -03:00
|
|
|
|
2016-03-08 02:17:51 -04:00
|
|
|
if (msg->msgid == MAVLINK_MSG_ID_MISSION_REQUEST_INT) {
|
|
|
|
// decode
|
|
|
|
mavlink_mission_request_int_t packet;
|
|
|
|
mavlink_msg_mission_request_int_decode(msg, &packet);
|
2014-03-17 23:52:07 -03:00
|
|
|
|
2016-03-08 02:17:51 -04:00
|
|
|
// retrieve mission from eeprom
|
|
|
|
if (!mission.read_cmd_from_storage(packet.seq, cmd)) {
|
|
|
|
goto mission_item_send_failed;
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_mission_item_int_t ret_packet;
|
|
|
|
memset(&ret_packet, 0, sizeof(ret_packet));
|
|
|
|
if (!AP_Mission::mission_cmd_to_mavlink_int(cmd, ret_packet)) {
|
|
|
|
goto mission_item_send_failed;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set packet's current field to 1 if this is the command being executed
|
|
|
|
if (cmd.id == (uint16_t)mission.get_current_nav_cmd().index) {
|
|
|
|
ret_packet.current = 1;
|
|
|
|
} else {
|
|
|
|
ret_packet.current = 0;
|
|
|
|
}
|
2014-03-17 23:52:07 -03:00
|
|
|
|
2016-03-08 02:17:51 -04:00
|
|
|
// set auto continue to 1
|
|
|
|
ret_packet.autocontinue = 1; // 1 (true), 0 (false)
|
|
|
|
|
|
|
|
/*
|
|
|
|
avoid the _send() function to save memory, as it avoids
|
|
|
|
the stack usage of the _send() function by using the already
|
|
|
|
declared ret_packet above
|
|
|
|
*/
|
|
|
|
ret_packet.target_system = msg->sysid;
|
|
|
|
ret_packet.target_component = msg->compid;
|
|
|
|
ret_packet.seq = packet.seq;
|
|
|
|
ret_packet.command = cmd.id;
|
|
|
|
|
|
|
|
_mav_finalize_message_chan_send(chan,
|
|
|
|
MAVLINK_MSG_ID_MISSION_ITEM_INT,
|
|
|
|
(const char *)&ret_packet,
|
2016-04-06 06:30:03 -03:00
|
|
|
MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN,
|
2016-03-08 02:17:51 -04:00
|
|
|
MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN,
|
|
|
|
MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
|
2014-03-17 23:52:07 -03:00
|
|
|
} else {
|
2016-03-08 02:17:51 -04:00
|
|
|
// decode
|
|
|
|
mavlink_mission_request_t packet;
|
|
|
|
mavlink_msg_mission_request_decode(msg, &packet);
|
2014-03-17 23:52:07 -03:00
|
|
|
|
2017-04-03 00:32:12 -03:00
|
|
|
if (packet.seq != 0 && // always allow HOME to be read
|
|
|
|
packet.seq >= mission.num_commands()) {
|
2017-01-21 01:01:10 -04:00
|
|
|
// try to educate the GCS on the actual size of the mission:
|
2017-04-11 08:41:45 -03:00
|
|
|
mavlink_msg_mission_count_send(chan,msg->sysid, msg->compid, mission.num_commands(),
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2017-01-21 01:01:10 -04:00
|
|
|
goto mission_item_send_failed;
|
|
|
|
}
|
|
|
|
|
2016-03-08 02:17:51 -04:00
|
|
|
// retrieve mission from eeprom
|
|
|
|
if (!mission.read_cmd_from_storage(packet.seq, cmd)) {
|
|
|
|
goto mission_item_send_failed;
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_mission_item_t ret_packet;
|
|
|
|
memset(&ret_packet, 0, sizeof(ret_packet));
|
|
|
|
if (!AP_Mission::mission_cmd_to_mavlink(cmd, ret_packet)) {
|
|
|
|
goto mission_item_send_failed;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set packet's current field to 1 if this is the command being executed
|
|
|
|
if (cmd.id == (uint16_t)mission.get_current_nav_cmd().index) {
|
|
|
|
ret_packet.current = 1;
|
|
|
|
} else {
|
|
|
|
ret_packet.current = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set auto continue to 1
|
|
|
|
ret_packet.autocontinue = 1; // 1 (true), 0 (false)
|
|
|
|
|
|
|
|
/*
|
|
|
|
avoid the _send() function to save memory, as it avoids
|
|
|
|
the stack usage of the _send() function by using the already
|
|
|
|
declared ret_packet above
|
|
|
|
*/
|
|
|
|
ret_packet.target_system = msg->sysid;
|
|
|
|
ret_packet.target_component = msg->compid;
|
|
|
|
ret_packet.seq = packet.seq;
|
|
|
|
ret_packet.command = cmd.id;
|
|
|
|
|
|
|
|
_mav_finalize_message_chan_send(chan,
|
|
|
|
MAVLINK_MSG_ID_MISSION_ITEM,
|
|
|
|
(const char *)&ret_packet,
|
2016-04-06 06:30:03 -03:00
|
|
|
MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN,
|
2016-03-08 02:17:51 -04:00
|
|
|
MAVLINK_MSG_ID_MISSION_ITEM_LEN,
|
|
|
|
MAVLINK_MSG_ID_MISSION_ITEM_CRC);
|
|
|
|
}
|
2014-03-17 23:52:07 -03:00
|
|
|
|
|
|
|
return;
|
|
|
|
|
|
|
|
mission_item_send_failed:
|
|
|
|
// send failure message
|
2017-04-11 08:41:45 -03:00
|
|
|
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ERROR,
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2014-03-17 23:52:07 -03:00
|
|
|
}
|
2014-03-18 10:30:59 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
handle a MISSION_SET_CURRENT mavlink packet
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_mission_set_current_t packet;
|
|
|
|
mavlink_msg_mission_set_current_decode(msg, &packet);
|
|
|
|
|
|
|
|
// set current command
|
|
|
|
if (mission.set_current_cmd(packet.seq)) {
|
2016-09-03 01:27:44 -03:00
|
|
|
mavlink_msg_mission_current_send(chan, packet.seq);
|
2014-03-18 10:30:59 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
handle a MISSION_COUNT mavlink packet
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_mission_count(AP_Mission &mission, mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_mission_count_t packet;
|
|
|
|
mavlink_msg_mission_count_decode(msg, &packet);
|
|
|
|
|
|
|
|
// start waypoint receiving
|
|
|
|
if (packet.count > mission.num_commands_max()) {
|
|
|
|
// send NAK
|
2017-04-11 08:41:45 -03:00
|
|
|
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_NO_SPACE,
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2014-03-18 10:30:59 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// new mission arriving, truncate mission to be the same length
|
|
|
|
mission.truncate(packet.count);
|
|
|
|
|
|
|
|
// set variables to help handle the expected receiving of commands from the GCS
|
2015-11-19 23:15:38 -04:00
|
|
|
waypoint_timelast_receive = AP_HAL::millis(); // set time we last received commands to now
|
2014-03-18 10:30:59 -03:00
|
|
|
waypoint_receiving = true; // record that we expect to receive commands
|
|
|
|
waypoint_request_i = 0; // reset the next expected command number to zero
|
|
|
|
waypoint_request_last = packet.count; // record how many commands we expect to receive
|
|
|
|
waypoint_timelast_request = 0; // set time we last requested commands to zero
|
2017-10-10 22:16:20 -03:00
|
|
|
|
|
|
|
waypoint_dest_sysid = msg->sysid; // record system id of GCS who wants to upload the mission
|
|
|
|
waypoint_dest_compid = msg->compid; // record component id of GCS who wants to upload the mission
|
2014-03-18 10:30:59 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
handle a MISSION_CLEAR_ALL mavlink packet
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_mission_clear_all(AP_Mission &mission, mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_mission_clear_all_t packet;
|
|
|
|
mavlink_msg_mission_clear_all_decode(msg, &packet);
|
|
|
|
|
|
|
|
// clear all waypoints
|
|
|
|
if (mission.clear()) {
|
|
|
|
// send ack
|
2017-04-11 08:41:45 -03:00
|
|
|
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_RESULT_ACCEPTED,
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2014-03-18 10:30:59 -03:00
|
|
|
}else{
|
|
|
|
// send nack
|
2017-04-11 08:41:45 -03:00
|
|
|
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ERROR,
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2014-03-18 10:30:59 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
handle a MISSION_WRITE_PARTIAL_LIST mavlink packet
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_mission_write_partial_list(AP_Mission &mission, mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_mission_write_partial_list_t packet;
|
|
|
|
mavlink_msg_mission_write_partial_list_decode(msg, &packet);
|
|
|
|
|
|
|
|
// start waypoint receiving
|
2014-03-23 22:52:39 -03:00
|
|
|
if ((unsigned)packet.start_index > mission.num_commands() ||
|
|
|
|
(unsigned)packet.end_index > mission.num_commands() ||
|
2014-03-18 10:30:59 -03:00
|
|
|
packet.end_index < packet.start_index) {
|
2015-11-25 17:08:58 -04:00
|
|
|
send_text(MAV_SEVERITY_WARNING,"Flight plan update rejected");
|
2014-03-18 10:30:59 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-11-19 23:15:38 -04:00
|
|
|
waypoint_timelast_receive = AP_HAL::millis();
|
2014-03-18 10:30:59 -03:00
|
|
|
waypoint_timelast_request = 0;
|
|
|
|
waypoint_receiving = true;
|
|
|
|
waypoint_request_i = packet.start_index;
|
|
|
|
waypoint_request_last= packet.end_index;
|
2018-02-06 21:22:08 -04:00
|
|
|
|
|
|
|
waypoint_dest_sysid = msg->sysid; // record system id of GCS who wants to partially update the mission
|
|
|
|
waypoint_dest_compid = msg->compid; // record component id of GCS who wants to partially update the mission
|
2014-03-18 10:30:59 -03:00
|
|
|
}
|
2014-03-18 16:43:22 -03:00
|
|
|
|
2015-01-29 05:01:29 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
handle a GIMBAL_REPORT mavlink packet
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const
|
|
|
|
{
|
|
|
|
mount.handle_gimbal_report(chan, msg);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2017-07-09 05:31:30 -03:00
|
|
|
void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
2014-03-18 18:34:16 -03:00
|
|
|
{
|
2017-07-09 05:31:30 -03:00
|
|
|
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] {};
|
|
|
|
va_list arg_list;
|
|
|
|
va_start(arg_list, fmt);
|
|
|
|
hal.util->vsnprintf((char *)text, sizeof(text), fmt, arg_list);
|
|
|
|
va_end(arg_list);
|
|
|
|
gcs().send_statustext(severity, (1<<chan), text);
|
2014-03-18 18:34:16 -03:00
|
|
|
}
|
|
|
|
|
2014-03-19 19:55:04 -03:00
|
|
|
void GCS_MAVLINK::handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio)
|
2014-03-18 18:44:58 -03:00
|
|
|
{
|
|
|
|
mavlink_radio_t packet;
|
|
|
|
mavlink_msg_radio_decode(msg, &packet);
|
|
|
|
|
|
|
|
// record if the GCS has been receiving radio messages from
|
|
|
|
// the aircraft
|
|
|
|
if (packet.remrssi != 0) {
|
2015-11-19 23:15:38 -04:00
|
|
|
last_radio_status_remrssi_ms = AP_HAL::millis();
|
2014-03-18 18:44:58 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// use the state of the transmit buffer in the radio to
|
|
|
|
// control the stream rate, giving us adaptive software
|
|
|
|
// flow control
|
|
|
|
if (packet.txbuf < 20 && stream_slowdown < 100) {
|
|
|
|
// we are very low on space - slow down a lot
|
|
|
|
stream_slowdown += 3;
|
|
|
|
} else if (packet.txbuf < 50 && stream_slowdown < 100) {
|
|
|
|
// we are a bit low on space, slow down slightly
|
|
|
|
stream_slowdown += 1;
|
|
|
|
} else if (packet.txbuf > 95 && stream_slowdown > 10) {
|
|
|
|
// the buffer has plenty of space, speed up a lot
|
|
|
|
stream_slowdown -= 2;
|
|
|
|
} else if (packet.txbuf > 90 && stream_slowdown != 0) {
|
|
|
|
// the buffer has enough space, speed up a bit
|
|
|
|
stream_slowdown--;
|
|
|
|
}
|
2014-03-19 19:55:04 -03:00
|
|
|
|
|
|
|
//log rssi, noise, etc if logging Performance monitoring data
|
|
|
|
if (log_radio) {
|
|
|
|
dataflash.Log_Write_Radio(packet);
|
|
|
|
}
|
2014-03-18 18:44:58 -03:00
|
|
|
}
|
2014-03-18 19:59:40 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
handle an incoming mission item
|
2015-05-05 18:39:16 -03:00
|
|
|
return true if this is the last mission item, otherwise false
|
2014-03-18 19:59:40 -03:00
|
|
|
*/
|
2015-05-05 18:39:16 -03:00
|
|
|
bool GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &mission)
|
2014-03-18 19:59:40 -03:00
|
|
|
{
|
2015-05-05 18:39:16 -03:00
|
|
|
MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED;
|
2014-03-18 19:59:40 -03:00
|
|
|
struct AP_Mission::Mission_Command cmd = {};
|
2015-05-05 18:39:16 -03:00
|
|
|
bool mission_is_complete = false;
|
2016-03-08 02:17:51 -04:00
|
|
|
uint16_t seq=0;
|
|
|
|
uint16_t current = 0;
|
|
|
|
|
|
|
|
if (msg->msgid == MAVLINK_MSG_ID_MISSION_ITEM) {
|
|
|
|
mavlink_mission_item_t packet;
|
|
|
|
mavlink_msg_mission_item_decode(msg, &packet);
|
|
|
|
|
|
|
|
// convert mavlink packet to mission command
|
|
|
|
result = AP_Mission::mavlink_to_mission_cmd(packet, cmd);
|
|
|
|
if (result != MAV_MISSION_ACCEPTED) {
|
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
|
|
|
|
seq = packet.seq;
|
|
|
|
current = packet.current;
|
|
|
|
} else {
|
|
|
|
mavlink_mission_item_int_t packet;
|
|
|
|
mavlink_msg_mission_item_int_decode(msg, &packet);
|
|
|
|
|
|
|
|
// convert mavlink packet to mission command
|
|
|
|
result = AP_Mission::mavlink_int_to_mission_cmd(packet, cmd);
|
|
|
|
if (result != MAV_MISSION_ACCEPTED) {
|
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
|
|
|
|
seq = packet.seq;
|
|
|
|
current = packet.current;
|
2014-03-18 19:59:40 -03:00
|
|
|
}
|
|
|
|
|
2016-03-08 02:17:51 -04:00
|
|
|
if (current == 2) {
|
2014-03-18 19:59:40 -03:00
|
|
|
// current = 2 is a flag to tell us this is a "guided mode"
|
|
|
|
// waypoint and not for the mission
|
2016-04-26 07:08:36 -03:00
|
|
|
result = (handle_guided_request(cmd) ? MAV_MISSION_ACCEPTED
|
|
|
|
: MAV_MISSION_ERROR) ;
|
2014-03-18 19:59:40 -03:00
|
|
|
|
2014-05-26 04:01:11 -03:00
|
|
|
// verify we received the command
|
2014-03-18 19:59:40 -03:00
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
|
2016-03-08 02:17:51 -04:00
|
|
|
if (current == 3) {
|
2014-03-18 19:59:40 -03:00
|
|
|
//current = 3 is a flag to tell us this is a alt change only
|
|
|
|
// add home alt if needed
|
|
|
|
handle_change_alt_request(cmd);
|
|
|
|
|
|
|
|
// verify we recevied the command
|
2015-05-05 18:39:16 -03:00
|
|
|
result = MAV_MISSION_ACCEPTED;
|
2014-03-18 19:59:40 -03:00
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Check if receiving waypoints (mission upload expected)
|
|
|
|
if (!waypoint_receiving) {
|
|
|
|
result = MAV_MISSION_ERROR;
|
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if this is the requested waypoint
|
2016-03-08 02:17:51 -04:00
|
|
|
if (seq != waypoint_request_i) {
|
2014-03-18 19:59:40 -03:00
|
|
|
result = MAV_MISSION_INVALID_SEQUENCE;
|
|
|
|
goto mission_ack;
|
|
|
|
}
|
2016-06-14 04:34:17 -03:00
|
|
|
|
|
|
|
// sanity check for DO_JUMP command
|
|
|
|
if (cmd.id == MAV_CMD_DO_JUMP) {
|
|
|
|
if ((cmd.content.jump.target >= mission.num_commands() && cmd.content.jump.target >= waypoint_request_last) || cmd.content.jump.target == 0) {
|
|
|
|
result = MAV_MISSION_ERROR;
|
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
}
|
2014-03-18 19:59:40 -03:00
|
|
|
|
|
|
|
// if command index is within the existing list, replace the command
|
2016-03-08 02:17:51 -04:00
|
|
|
if (seq < mission.num_commands()) {
|
|
|
|
if (mission.replace_cmd(seq,cmd)) {
|
2014-03-18 19:59:40 -03:00
|
|
|
result = MAV_MISSION_ACCEPTED;
|
|
|
|
}else{
|
|
|
|
result = MAV_MISSION_ERROR;
|
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
// if command is at the end of command list, add the command
|
2016-03-08 02:17:51 -04:00
|
|
|
} else if (seq == mission.num_commands()) {
|
2014-03-18 19:59:40 -03:00
|
|
|
if (mission.add_cmd(cmd)) {
|
|
|
|
result = MAV_MISSION_ACCEPTED;
|
|
|
|
}else{
|
|
|
|
result = MAV_MISSION_ERROR;
|
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
// if beyond the end of the command list, return an error
|
|
|
|
} else {
|
|
|
|
result = MAV_MISSION_ERROR;
|
|
|
|
goto mission_ack;
|
|
|
|
}
|
|
|
|
|
|
|
|
// update waypoint receiving state machine
|
2015-11-19 23:15:38 -04:00
|
|
|
waypoint_timelast_receive = AP_HAL::millis();
|
2014-03-18 19:59:40 -03:00
|
|
|
waypoint_request_i++;
|
|
|
|
|
|
|
|
if (waypoint_request_i >= waypoint_request_last) {
|
|
|
|
mavlink_msg_mission_ack_send_buf(
|
|
|
|
msg,
|
|
|
|
chan,
|
|
|
|
msg->sysid,
|
|
|
|
msg->compid,
|
2017-04-11 08:41:45 -03:00
|
|
|
MAV_MISSION_ACCEPTED,
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2014-03-18 19:59:40 -03:00
|
|
|
|
2015-11-25 17:08:58 -04:00
|
|
|
send_text(MAV_SEVERITY_INFO,"Flight plan received");
|
2014-03-18 19:59:40 -03:00
|
|
|
waypoint_receiving = false;
|
2015-05-05 18:39:16 -03:00
|
|
|
mission_is_complete = true;
|
2014-03-18 19:59:40 -03:00
|
|
|
// XXX ignores waypoint radius for individual waypoints, can
|
|
|
|
// only set WP_RADIUS parameter
|
|
|
|
} else {
|
2015-11-19 23:15:38 -04:00
|
|
|
waypoint_timelast_request = AP_HAL::millis();
|
2014-03-18 19:59:40 -03:00
|
|
|
// if we have enough space, then send the next WP immediately
|
2016-04-05 01:09:47 -03:00
|
|
|
if (HAVE_PAYLOAD_SPACE(chan, MISSION_ITEM)) {
|
2014-03-18 19:59:40 -03:00
|
|
|
queued_waypoint_send();
|
|
|
|
} else {
|
|
|
|
send_message(MSG_NEXT_WAYPOINT);
|
|
|
|
}
|
|
|
|
}
|
2015-05-05 18:39:16 -03:00
|
|
|
return mission_is_complete;
|
2014-03-18 19:59:40 -03:00
|
|
|
|
|
|
|
mission_ack:
|
|
|
|
// we are rejecting the mission/waypoint
|
|
|
|
mavlink_msg_mission_ack_send_buf(
|
|
|
|
msg,
|
|
|
|
chan,
|
|
|
|
msg->sysid,
|
|
|
|
msg->compid,
|
2017-04-11 08:41:45 -03:00
|
|
|
result,
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2015-05-05 18:39:16 -03:00
|
|
|
|
|
|
|
return mission_is_complete;
|
2014-03-18 19:59:40 -03:00
|
|
|
}
|
2014-03-18 20:56:09 -03:00
|
|
|
|
2017-07-18 22:36:49 -03:00
|
|
|
void GCS_MAVLINK::push_deferred_messages()
|
2014-03-18 20:56:09 -03:00
|
|
|
{
|
|
|
|
while (num_deferred_messages != 0) {
|
|
|
|
if (!try_send_message(deferred_messages[next_deferred_message])) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
next_deferred_message++;
|
2017-07-17 01:35:17 -03:00
|
|
|
if (next_deferred_message == ARRAY_SIZE(deferred_messages)) {
|
2014-03-18 20:56:09 -03:00
|
|
|
next_deferred_message = 0;
|
|
|
|
}
|
|
|
|
num_deferred_messages--;
|
|
|
|
}
|
2017-07-18 22:36:49 -03:00
|
|
|
}
|
2014-03-18 20:56:09 -03:00
|
|
|
|
2017-07-18 22:36:49 -03:00
|
|
|
void GCS_MAVLINK::retry_deferred()
|
|
|
|
{
|
|
|
|
push_deferred_messages();
|
|
|
|
}
|
|
|
|
|
|
|
|
// send a message using mavlink, handling message queueing
|
|
|
|
void GCS_MAVLINK::send_message(enum ap_message id)
|
|
|
|
{
|
|
|
|
uint8_t i, nextid;
|
|
|
|
|
|
|
|
if (id == MSG_HEARTBEAT) {
|
|
|
|
save_signing_timestamp(false);
|
2014-03-18 20:56:09 -03:00
|
|
|
}
|
|
|
|
|
2017-07-18 22:36:49 -03:00
|
|
|
// see if we can send the deferred messages, if any:
|
|
|
|
push_deferred_messages();
|
|
|
|
|
2017-07-17 01:35:17 -03:00
|
|
|
// if there are no deferred messages, attempt to send straight away:
|
|
|
|
if (num_deferred_messages == 0) {
|
|
|
|
if (try_send_message(id)) {
|
|
|
|
// yay, we sent it!
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// we failed to send the message this time around, so try to defer:
|
|
|
|
if (num_deferred_messages == ARRAY_SIZE(deferred_messages)) {
|
|
|
|
// the defer buffer is full, discard this attempt to send.
|
|
|
|
// Note that the message *may* already be in the defer buffer
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if this message is deferred:
|
2014-03-18 20:56:09 -03:00
|
|
|
for (i=0, nextid = next_deferred_message; i < num_deferred_messages; i++) {
|
|
|
|
if (deferred_messages[nextid] == id) {
|
2017-07-17 01:35:17 -03:00
|
|
|
// it's already deferred
|
2014-03-18 20:56:09 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
nextid++;
|
2017-07-17 01:35:17 -03:00
|
|
|
if (nextid == ARRAY_SIZE(deferred_messages)) {
|
2014-03-18 20:56:09 -03:00
|
|
|
nextid = 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-07-17 01:35:17 -03:00
|
|
|
// not already deferred, defer it
|
|
|
|
deferred_messages[nextid] = id;
|
|
|
|
num_deferred_messages++;
|
2014-03-18 20:56:09 -03:00
|
|
|
}
|
2014-05-20 23:38:07 -03:00
|
|
|
|
2016-06-14 22:04:40 -03:00
|
|
|
void GCS_MAVLINK::packetReceived(const mavlink_status_t &status,
|
|
|
|
mavlink_message_t &msg)
|
|
|
|
{
|
2017-08-11 00:50:13 -03:00
|
|
|
// we exclude radio packets because we historically used this to
|
|
|
|
// make it possible to use the CLI over the radio
|
2016-06-14 22:04:40 -03:00
|
|
|
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
|
|
|
|
mavlink_active |= (1U<<(chan-MAVLINK_COMM_0));
|
|
|
|
}
|
|
|
|
if (!(status.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) &&
|
|
|
|
(status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) &&
|
|
|
|
serialmanager_p &&
|
|
|
|
serialmanager_p->get_mavlink_protocol(chan) == AP_SerialManager::SerialProtocol_MAVLink2) {
|
|
|
|
// if we receive any MAVLink2 packets on a connection
|
|
|
|
// currently sending MAVLink1 then switch to sending
|
|
|
|
// MAVLink2
|
|
|
|
mavlink_status_t *cstatus = mavlink_get_channel_status(chan);
|
2016-10-30 02:24:21 -03:00
|
|
|
if (cstatus != nullptr) {
|
2016-06-14 22:04:40 -03:00
|
|
|
cstatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
// if a snoop handler has been setup then use it
|
2016-10-30 02:24:21 -03:00
|
|
|
if (msg_snoop != nullptr) {
|
2016-06-14 22:04:40 -03:00
|
|
|
msg_snoop(&msg);
|
|
|
|
}
|
2016-08-13 18:42:40 -03:00
|
|
|
if (routing.check_and_forward(chan, &msg) &&
|
|
|
|
accept_packet(status, msg)) {
|
2016-06-14 22:04:40 -03:00
|
|
|
handleMessage(&msg);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-05-20 23:38:07 -03:00
|
|
|
void
|
2017-08-11 00:50:13 -03:00
|
|
|
GCS_MAVLINK::update(uint32_t max_time_us)
|
2014-05-20 23:38:07 -03:00
|
|
|
{
|
|
|
|
// receive new packets
|
|
|
|
mavlink_message_t msg;
|
|
|
|
mavlink_status_t status;
|
2017-04-28 01:35:53 -03:00
|
|
|
uint32_t tstart_us = AP_HAL::micros();
|
|
|
|
|
|
|
|
hal.util->perf_begin(_perf_update);
|
|
|
|
|
2014-05-20 23:38:07 -03:00
|
|
|
status.packet_rx_drop_count = 0;
|
|
|
|
|
|
|
|
// process received bytes
|
|
|
|
uint16_t nbytes = comm_get_available(chan);
|
|
|
|
for (uint16_t i=0; i<nbytes; i++)
|
|
|
|
{
|
|
|
|
uint8_t c = comm_receive_ch(chan);
|
|
|
|
|
2017-04-28 01:35:53 -03:00
|
|
|
bool parsed_packet = false;
|
|
|
|
|
2014-05-20 23:38:07 -03:00
|
|
|
// Try to get a new message
|
|
|
|
if (mavlink_parse_char(chan, c, &msg, &status)) {
|
2017-04-28 01:35:53 -03:00
|
|
|
hal.util->perf_begin(_perf_packet);
|
2016-06-14 22:04:40 -03:00
|
|
|
packetReceived(status, msg);
|
2017-04-28 01:35:53 -03:00
|
|
|
hal.util->perf_end(_perf_packet);
|
|
|
|
parsed_packet = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (parsed_packet || i % 100 == 0) {
|
|
|
|
// make sure we don't spend too much time parsing mavlink messages
|
|
|
|
if (AP_HAL::micros() - tstart_us > max_time_us) {
|
|
|
|
break;
|
|
|
|
}
|
2014-05-20 23:38:07 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!waypoint_receiving) {
|
2017-04-28 01:35:53 -03:00
|
|
|
hal.util->perf_end(_perf_update);
|
2014-05-20 23:38:07 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-11-19 23:15:38 -04:00
|
|
|
uint32_t tnow = AP_HAL::millis();
|
2014-05-20 23:38:07 -03:00
|
|
|
uint32_t wp_recv_time = 1000U + (stream_slowdown*20);
|
|
|
|
|
|
|
|
// stop waypoint receiving if timeout
|
|
|
|
if (waypoint_receiving && (tnow - waypoint_timelast_receive) > wp_recv_time+waypoint_receive_timeout) {
|
|
|
|
waypoint_receiving = false;
|
2016-06-22 05:13:11 -03:00
|
|
|
} else if (waypoint_receiving &&
|
|
|
|
(tnow - waypoint_timelast_request) > wp_recv_time) {
|
|
|
|
waypoint_timelast_request = tnow;
|
|
|
|
send_message(MSG_NEXT_WAYPOINT);
|
2014-05-20 23:38:07 -03:00
|
|
|
}
|
2016-06-22 05:13:11 -03:00
|
|
|
|
2017-04-28 01:35:53 -03:00
|
|
|
hal.util->perf_end(_perf_update);
|
2014-05-20 23:38:07 -03:00
|
|
|
}
|
2014-05-27 20:35:30 -03:00
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
send the SYSTEM_TIME message
|
|
|
|
*/
|
2017-10-25 01:32:35 -03:00
|
|
|
void GCS_MAVLINK::send_system_time()
|
2014-05-27 20:35:30 -03:00
|
|
|
{
|
|
|
|
mavlink_msg_system_time_send(
|
|
|
|
chan,
|
2017-10-25 01:32:35 -03:00
|
|
|
AP::gps().time_epoch_usec(),
|
2015-11-19 23:15:38 -04:00
|
|
|
AP_HAL::millis());
|
2014-05-27 20:35:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
2016-10-13 21:40:36 -03:00
|
|
|
send RC_CHANNELS messages
|
2014-05-27 20:35:30 -03:00
|
|
|
*/
|
2014-08-16 08:31:14 -03:00
|
|
|
void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi)
|
2014-05-27 20:35:30 -03:00
|
|
|
{
|
2015-11-19 23:15:38 -04:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2016-10-18 04:16:16 -03:00
|
|
|
mavlink_status_t *status = mavlink_get_channel_status(chan);
|
2014-05-27 20:35:30 -03:00
|
|
|
|
2016-10-13 07:23:39 -03:00
|
|
|
uint16_t values[18];
|
2014-05-27 20:35:30 -03:00
|
|
|
memset(values, 0, sizeof(values));
|
2016-10-13 07:23:39 -03:00
|
|
|
hal.rcin->read(values, 18);
|
2014-05-27 20:35:30 -03:00
|
|
|
|
2016-10-18 04:16:16 -03:00
|
|
|
if (status && (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
|
|
|
|
// for mavlink1 send RC_CHANNELS_RAW, for compatibility with OSD implementations
|
|
|
|
mavlink_msg_rc_channels_raw_send(
|
|
|
|
chan,
|
|
|
|
now,
|
|
|
|
0,
|
|
|
|
values[0],
|
|
|
|
values[1],
|
|
|
|
values[2],
|
|
|
|
values[3],
|
|
|
|
values[4],
|
|
|
|
values[5],
|
|
|
|
values[6],
|
|
|
|
values[7],
|
|
|
|
receiver_rssi);
|
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, RC_CHANNELS)) {
|
|
|
|
// can't fit RC_CHANNELS
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2016-10-13 07:23:39 -03:00
|
|
|
mavlink_msg_rc_channels_send(
|
2014-05-27 20:35:30 -03:00
|
|
|
chan,
|
|
|
|
now,
|
2016-10-13 07:23:39 -03:00
|
|
|
hal.rcin->num_channels(),
|
2014-08-16 08:31:14 -03:00
|
|
|
values[0],
|
|
|
|
values[1],
|
|
|
|
values[2],
|
|
|
|
values[3],
|
2014-05-27 20:35:30 -03:00
|
|
|
values[4],
|
|
|
|
values[5],
|
|
|
|
values[6],
|
|
|
|
values[7],
|
2016-10-13 07:23:39 -03:00
|
|
|
values[8],
|
|
|
|
values[9],
|
|
|
|
values[10],
|
|
|
|
values[11],
|
|
|
|
values[12],
|
|
|
|
values[13],
|
|
|
|
values[14],
|
|
|
|
values[15],
|
|
|
|
values[16],
|
|
|
|
values[17],
|
|
|
|
receiver_rssi);
|
2014-05-27 20:35:30 -03:00
|
|
|
}
|
2014-07-13 02:31:25 -03:00
|
|
|
|
|
|
|
void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &compass)
|
|
|
|
{
|
|
|
|
const Vector3f &accel = ins.get_accel(0);
|
|
|
|
const Vector3f &gyro = ins.get_gyro(0);
|
2015-03-04 04:30:08 -04:00
|
|
|
Vector3f mag;
|
|
|
|
if (compass.get_count() >= 1) {
|
2015-10-07 20:39:02 -03:00
|
|
|
mag = compass.get_field(0);
|
2015-03-04 04:30:08 -04:00
|
|
|
} else {
|
|
|
|
mag.zero();
|
|
|
|
}
|
2014-07-13 02:31:25 -03:00
|
|
|
|
|
|
|
mavlink_msg_raw_imu_send(
|
|
|
|
chan,
|
2015-11-19 23:15:38 -04:00
|
|
|
AP_HAL::micros(),
|
2014-07-13 02:31:25 -03:00
|
|
|
accel.x * 1000.0f / GRAVITY_MSS,
|
|
|
|
accel.y * 1000.0f / GRAVITY_MSS,
|
|
|
|
accel.z * 1000.0f / GRAVITY_MSS,
|
|
|
|
gyro.x * 1000.0f,
|
|
|
|
gyro.y * 1000.0f,
|
|
|
|
gyro.z * 1000.0f,
|
|
|
|
mag.x,
|
|
|
|
mag.y,
|
|
|
|
mag.z);
|
2015-10-14 12:49:38 -03:00
|
|
|
|
2014-07-13 02:31:25 -03:00
|
|
|
if (ins.get_gyro_count() <= 1 &&
|
|
|
|
ins.get_accel_count() <= 1 &&
|
|
|
|
compass.get_count() <= 1) {
|
|
|
|
return;
|
|
|
|
}
|
2016-05-23 09:02:12 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, SCALED_IMU2)) {
|
|
|
|
return;
|
|
|
|
}
|
2014-07-13 02:31:25 -03:00
|
|
|
const Vector3f &accel2 = ins.get_accel(1);
|
|
|
|
const Vector3f &gyro2 = ins.get_gyro(1);
|
2015-03-04 04:30:08 -04:00
|
|
|
if (compass.get_count() >= 2) {
|
2015-10-07 20:39:02 -03:00
|
|
|
mag = compass.get_field(1);
|
2015-03-04 04:30:08 -04:00
|
|
|
} else {
|
|
|
|
mag.zero();
|
|
|
|
}
|
2014-07-13 02:31:25 -03:00
|
|
|
mavlink_msg_scaled_imu2_send(
|
|
|
|
chan,
|
2015-11-19 23:15:38 -04:00
|
|
|
AP_HAL::millis(),
|
2014-07-13 02:31:25 -03:00
|
|
|
accel2.x * 1000.0f / GRAVITY_MSS,
|
|
|
|
accel2.y * 1000.0f / GRAVITY_MSS,
|
|
|
|
accel2.z * 1000.0f / GRAVITY_MSS,
|
|
|
|
gyro2.x * 1000.0f,
|
|
|
|
gyro2.y * 1000.0f,
|
|
|
|
gyro2.z * 1000.0f,
|
2015-03-04 04:30:08 -04:00
|
|
|
mag.x,
|
|
|
|
mag.y,
|
|
|
|
mag.z);
|
2015-10-14 12:49:38 -03:00
|
|
|
|
2015-03-04 04:30:08 -04:00
|
|
|
if (ins.get_gyro_count() <= 2 &&
|
|
|
|
ins.get_accel_count() <= 2 &&
|
|
|
|
compass.get_count() <= 2) {
|
|
|
|
return;
|
|
|
|
}
|
2016-05-23 09:02:12 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, SCALED_IMU3)) {
|
|
|
|
return;
|
|
|
|
}
|
2015-03-04 04:30:08 -04:00
|
|
|
const Vector3f &accel3 = ins.get_accel(2);
|
|
|
|
const Vector3f &gyro3 = ins.get_gyro(2);
|
|
|
|
if (compass.get_count() >= 3) {
|
2015-10-07 20:39:02 -03:00
|
|
|
mag = compass.get_field(2);
|
2015-03-04 04:30:08 -04:00
|
|
|
} else {
|
|
|
|
mag.zero();
|
|
|
|
}
|
|
|
|
mavlink_msg_scaled_imu3_send(
|
|
|
|
chan,
|
2015-11-19 23:15:38 -04:00
|
|
|
AP_HAL::millis(),
|
2015-03-04 04:30:08 -04:00
|
|
|
accel3.x * 1000.0f / GRAVITY_MSS,
|
|
|
|
accel3.y * 1000.0f / GRAVITY_MSS,
|
|
|
|
accel3.z * 1000.0f / GRAVITY_MSS,
|
|
|
|
gyro3.x * 1000.0f,
|
|
|
|
gyro3.y * 1000.0f,
|
|
|
|
gyro3.z * 1000.0f,
|
|
|
|
mag.x,
|
|
|
|
mag.y,
|
|
|
|
mag.z);
|
2014-07-13 02:31:25 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void GCS_MAVLINK::send_scaled_pressure(AP_Baro &barometer)
|
|
|
|
{
|
2015-11-19 23:15:38 -04:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2015-01-05 07:30:00 -04:00
|
|
|
float pressure = barometer.get_pressure(0);
|
2014-07-13 02:31:25 -03:00
|
|
|
mavlink_msg_scaled_pressure_send(
|
|
|
|
chan,
|
2015-01-05 07:30:00 -04:00
|
|
|
now,
|
2014-07-13 02:31:25 -03:00
|
|
|
pressure*0.01f, // hectopascal
|
2015-01-05 07:30:00 -04:00
|
|
|
(pressure - barometer.get_ground_pressure(0))*0.01f, // hectopascal
|
|
|
|
barometer.get_temperature(0)*100); // 0.01 degrees C
|
2015-10-14 12:57:21 -03:00
|
|
|
|
2016-05-23 09:02:12 -03:00
|
|
|
if (barometer.num_instances() > 1 &&
|
|
|
|
HAVE_PAYLOAD_SPACE(chan, SCALED_PRESSURE2)) {
|
2015-01-05 07:30:00 -04:00
|
|
|
pressure = barometer.get_pressure(1);
|
|
|
|
mavlink_msg_scaled_pressure2_send(
|
|
|
|
chan,
|
|
|
|
now,
|
|
|
|
pressure*0.01f, // hectopascal
|
|
|
|
(pressure - barometer.get_ground_pressure(1))*0.01f, // hectopascal
|
|
|
|
barometer.get_temperature(1)*100); // 0.01 degrees C
|
|
|
|
}
|
2015-10-14 12:57:21 -03:00
|
|
|
|
2016-05-23 09:02:12 -03:00
|
|
|
if (barometer.num_instances() > 2 &&
|
|
|
|
HAVE_PAYLOAD_SPACE(chan, SCALED_PRESSURE3)) {
|
2015-09-12 05:34:25 -03:00
|
|
|
pressure = barometer.get_pressure(2);
|
|
|
|
mavlink_msg_scaled_pressure3_send(
|
|
|
|
chan,
|
|
|
|
now,
|
|
|
|
pressure*0.01f, // hectopascal
|
|
|
|
(pressure - barometer.get_ground_pressure(2))*0.01f, // hectopascal
|
|
|
|
barometer.get_temperature(2)*100); // 0.01 degrees C
|
|
|
|
}
|
2014-07-13 02:31:25 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void GCS_MAVLINK::send_sensor_offsets(const AP_InertialSensor &ins, const Compass &compass, AP_Baro &barometer)
|
|
|
|
{
|
|
|
|
// run this message at a much lower rate - otherwise it
|
|
|
|
// pointlessly wastes quite a lot of bandwidth
|
|
|
|
static uint8_t counter;
|
|
|
|
if (counter++ < 10) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
counter = 0;
|
|
|
|
|
|
|
|
const Vector3f &mag_offsets = compass.get_offsets(0);
|
|
|
|
const Vector3f &accel_offsets = ins.get_accel_offsets(0);
|
|
|
|
const Vector3f &gyro_offsets = ins.get_gyro_offsets(0);
|
|
|
|
|
|
|
|
mavlink_msg_sensor_offsets_send(chan,
|
|
|
|
mag_offsets.x,
|
|
|
|
mag_offsets.y,
|
|
|
|
mag_offsets.z,
|
|
|
|
compass.get_declination(),
|
|
|
|
barometer.get_pressure(),
|
|
|
|
barometer.get_temperature()*100,
|
|
|
|
gyro_offsets.x,
|
|
|
|
gyro_offsets.y,
|
|
|
|
gyro_offsets.z,
|
|
|
|
accel_offsets.x,
|
|
|
|
accel_offsets.y,
|
|
|
|
accel_offsets.z);
|
|
|
|
}
|
|
|
|
|
|
|
|
void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs)
|
|
|
|
{
|
|
|
|
const Vector3f &omega_I = ahrs.get_gyro_drift();
|
|
|
|
mavlink_msg_ahrs_send(
|
|
|
|
chan,
|
|
|
|
omega_I.x,
|
|
|
|
omega_I.y,
|
|
|
|
omega_I.z,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
ahrs.get_error_rp(),
|
|
|
|
ahrs.get_error_yaw());
|
|
|
|
}
|
2014-08-08 00:45:06 -03:00
|
|
|
|
2016-02-23 16:50:57 -04:00
|
|
|
/*
|
|
|
|
send a statustext text string to specific MAVLink bitmask
|
|
|
|
*/
|
2016-05-30 07:05:00 -03:00
|
|
|
void GCS::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
|
2016-02-23 16:50:57 -04:00
|
|
|
{
|
2016-10-30 02:24:21 -03:00
|
|
|
if (dataflash_p != nullptr) {
|
2016-02-23 16:50:57 -04:00
|
|
|
dataflash_p->Log_Write_Message(text);
|
|
|
|
}
|
|
|
|
|
2016-10-26 19:06:54 -03:00
|
|
|
// add statustext message to FrSky lib queue
|
|
|
|
if (frsky_telemetry_p != NULL) {
|
|
|
|
frsky_telemetry_p->queue_message(severity, text);
|
|
|
|
}
|
|
|
|
|
2016-02-23 16:50:57 -04:00
|
|
|
// filter destination ports to only allow active ports.
|
|
|
|
statustext_t statustext{};
|
2016-05-30 07:05:00 -03:00
|
|
|
statustext.bitmask = (GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask() ) & dest_bitmask;
|
2016-02-23 16:50:57 -04:00
|
|
|
if (!statustext.bitmask) {
|
|
|
|
// nowhere to send
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
statustext.msg.severity = severity;
|
|
|
|
strncpy(statustext.msg.text, text, sizeof(statustext.msg.text));
|
|
|
|
|
|
|
|
// The force push will ensure comm links do not block other comm links forever if they fail.
|
|
|
|
// If we push to a full buffer then we overwrite the oldest entry, effectively removing the
|
|
|
|
// block but not until the buffer fills up.
|
|
|
|
_statustext_queue.push_force(statustext);
|
2016-02-23 18:15:44 -04:00
|
|
|
|
|
|
|
// try and send immediately if possible
|
|
|
|
service_statustext();
|
2017-07-08 20:51:51 -03:00
|
|
|
|
|
|
|
AP_Notify *notify = AP_Notify::instance();
|
|
|
|
if (notify) {
|
|
|
|
notify->send_text(text);
|
|
|
|
}
|
2016-02-23 16:50:57 -04:00
|
|
|
}
|
2016-05-30 07:05:00 -03:00
|
|
|
|
2016-02-23 16:50:57 -04:00
|
|
|
/*
|
|
|
|
send a statustext message to specific MAVLink connections in a bitmask
|
|
|
|
*/
|
2016-05-30 07:05:00 -03:00
|
|
|
void GCS::service_statustext(void)
|
2016-02-23 16:50:57 -04:00
|
|
|
{
|
|
|
|
// create bitmask of what mavlink ports we should send this text to.
|
|
|
|
// note, if sending to all ports, we only need to store the bitmask for each and the string only once.
|
|
|
|
// once we send over a link, clear the port but other busy ports bit may stay allowing for faster links
|
|
|
|
// to clear the bit and send quickly but slower links to still store the string. Regardless of mixed
|
2016-05-30 07:05:00 -03:00
|
|
|
// bitrates of ports, a maximum of _status_capacity strings can be buffered. Downside
|
|
|
|
// is if you have a super slow link mixed with a faster port, if there are _status_capacity
|
2016-02-23 16:50:57 -04:00
|
|
|
// strings in the slow queue then the next item can not be queued for the faster link
|
|
|
|
|
|
|
|
if (_statustext_queue.empty()) {
|
2016-02-23 18:15:44 -04:00
|
|
|
// nothing to do
|
|
|
|
return;
|
2014-08-08 00:45:06 -03:00
|
|
|
}
|
2016-02-23 16:50:57 -04:00
|
|
|
|
2016-05-30 07:05:00 -03:00
|
|
|
for (uint8_t idx=0; idx<_status_capacity; ) {
|
2016-02-23 18:15:44 -04:00
|
|
|
statustext_t *statustext = _statustext_queue[idx];
|
|
|
|
if (statustext == nullptr) {
|
|
|
|
break;
|
2016-02-23 16:50:57 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// try and send to all active mavlink ports listed in the statustext.bitmask
|
|
|
|
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
|
2016-02-23 18:15:44 -04:00
|
|
|
uint8_t chan_bit = (1U<<i);
|
2016-02-23 16:50:57 -04:00
|
|
|
// logical AND (&) to mask them together
|
2016-02-23 18:15:44 -04:00
|
|
|
if (statustext->bitmask & chan_bit) {
|
|
|
|
// something is queued on a port and that's the port index we're looped at
|
2016-02-23 16:50:57 -04:00
|
|
|
mavlink_channel_t chan_index = (mavlink_channel_t)(MAVLINK_COMM_0+i);
|
2016-04-05 01:09:47 -03:00
|
|
|
if (HAVE_PAYLOAD_SPACE(chan_index, STATUSTEXT)) {
|
2016-02-23 16:50:57 -04:00
|
|
|
// we have space so send then clear that channel bit on the mask
|
2016-02-23 18:15:44 -04:00
|
|
|
mavlink_msg_statustext_send(chan_index, statustext->msg.severity, statustext->msg.text);
|
|
|
|
statustext->bitmask &= ~chan_bit;
|
|
|
|
}
|
|
|
|
}
|
2016-02-23 16:50:57 -04:00
|
|
|
}
|
2016-02-23 18:15:44 -04:00
|
|
|
|
|
|
|
if (statustext->bitmask == 0) {
|
|
|
|
_statustext_queue.remove(idx);
|
|
|
|
} else {
|
|
|
|
// move to next index
|
|
|
|
idx++;
|
|
|
|
}
|
|
|
|
}
|
2014-08-08 00:45:06 -03:00
|
|
|
}
|
2014-08-08 23:14:06 -03:00
|
|
|
|
2017-02-13 06:57:50 -04:00
|
|
|
void GCS::send_message(enum ap_message id)
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<num_gcs(); i++) {
|
|
|
|
if (chan(i).initialised) {
|
|
|
|
chan(i).send_message(id);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-07-18 22:36:49 -03:00
|
|
|
void GCS::retry_deferred()
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<num_gcs(); i++) {
|
|
|
|
if (chan(i).initialised) {
|
|
|
|
chan(i).retry_deferred();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
service_statustext();
|
|
|
|
}
|
|
|
|
|
2017-02-13 06:57:50 -04:00
|
|
|
void GCS::data_stream_send()
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<num_gcs(); i++) {
|
|
|
|
if (chan(i).initialised) {
|
|
|
|
chan(i).data_stream_send();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void GCS::update(void)
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<num_gcs(); i++) {
|
|
|
|
if (chan(i).initialised) {
|
2017-08-11 00:50:13 -03:00
|
|
|
chan(i).update();
|
2017-02-13 06:57:50 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void GCS::send_mission_item_reached_message(uint16_t mission_index)
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<num_gcs(); i++) {
|
|
|
|
if (chan(i).initialised) {
|
|
|
|
chan(i).mission_item_reached_index = mission_index;
|
|
|
|
chan(i).send_message(MSG_MISSION_ITEM_REACHED);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void GCS::setup_uarts(AP_SerialManager &serial_manager)
|
|
|
|
{
|
|
|
|
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
|
|
|
chan(i).setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-08-08 23:14:06 -03:00
|
|
|
// report battery2 state
|
|
|
|
void GCS_MAVLINK::send_battery2(const AP_BattMonitor &battery)
|
|
|
|
{
|
2014-12-03 01:31:57 -04:00
|
|
|
if (battery.num_instances() > 1) {
|
2016-06-02 19:39:54 -03:00
|
|
|
int16_t current;
|
|
|
|
if (battery.has_current(1)) {
|
|
|
|
current = battery.current_amps(1) * 100; // 10*mA
|
|
|
|
} else {
|
|
|
|
current = -1;
|
|
|
|
}
|
|
|
|
mavlink_msg_battery2_send(chan, battery.voltage(1)*1000, current);
|
2014-08-08 23:14:06 -03:00
|
|
|
}
|
|
|
|
}
|
2014-10-01 01:19:04 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
handle a SET_MODE MAVLink message
|
|
|
|
*/
|
2017-08-11 02:52:09 -03:00
|
|
|
void GCS_MAVLINK::handle_set_mode(mavlink_message_t* msg)
|
2014-10-01 01:19:04 -03:00
|
|
|
{
|
|
|
|
mavlink_set_mode_t packet;
|
|
|
|
mavlink_msg_set_mode_decode(msg, &packet);
|
|
|
|
|
2017-09-15 23:29:54 -03:00
|
|
|
const MAV_MODE base_mode = (MAV_MODE)packet.base_mode;
|
|
|
|
const uint32_t custom_mode = packet.custom_mode;
|
|
|
|
|
|
|
|
const MAV_RESULT result = _set_mode_common(base_mode, custom_mode);
|
|
|
|
|
|
|
|
// send ACK or NAK
|
|
|
|
mavlink_msg_command_ack_send_buf(msg, chan, MAVLINK_MSG_ID_SET_MODE, result);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
code common to both SET_MODE mavlink message and command long set_mode msg
|
|
|
|
*/
|
|
|
|
MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE base_mode, const uint32_t custom_mode)
|
|
|
|
{
|
|
|
|
MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
|
2014-10-01 01:19:04 -03:00
|
|
|
// only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes
|
2017-09-15 23:29:54 -03:00
|
|
|
if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
|
|
|
|
if (set_mode(custom_mode)) {
|
2014-10-01 01:19:04 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
2017-09-15 23:29:54 -03:00
|
|
|
} else if (base_mode == (MAV_MODE)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
|
2014-10-01 01:19:04 -03:00
|
|
|
// set the safety switch position. Must be in a command by itself
|
2017-09-15 23:29:54 -03:00
|
|
|
if (custom_mode == 0) {
|
2014-10-01 01:19:04 -03:00
|
|
|
// turn safety off (pwm outputs flow to the motors)
|
|
|
|
hal.rcout->force_safety_off();
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2017-09-15 23:29:54 -03:00
|
|
|
} else if (custom_mode == 1) {
|
2014-10-01 01:19:04 -03:00
|
|
|
// turn safety on (no pwm outputs to the motors)
|
|
|
|
if (hal.rcout->force_safety_on()) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-09-15 23:29:54 -03:00
|
|
|
return result;
|
2014-10-01 01:19:04 -03:00
|
|
|
}
|
2015-01-03 00:53:22 -04:00
|
|
|
|
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
|
|
/*
|
|
|
|
send OPTICAL_FLOW message
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::send_opticalflow(AP_AHRS_NavEKF &ahrs, const OpticalFlow &optflow)
|
|
|
|
{
|
|
|
|
// exit immediately if no optical flow sensor or not healthy
|
|
|
|
if (!optflow.healthy()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get rates from sensor
|
|
|
|
const Vector2f &flowRate = optflow.flowRate();
|
|
|
|
const Vector2f &bodyRate = optflow.bodyRate();
|
|
|
|
float hagl = 0;
|
|
|
|
|
|
|
|
if (ahrs.have_inertial_nav()) {
|
2016-11-27 00:18:49 -04:00
|
|
|
|
|
|
|
ahrs.get_hagl(hagl);
|
2015-01-03 00:53:22 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// populate and send message
|
|
|
|
mavlink_msg_optical_flow_send(
|
|
|
|
chan,
|
2015-11-19 23:15:38 -04:00
|
|
|
AP_HAL::millis(),
|
2015-01-03 00:53:22 -04:00
|
|
|
0, // sensor id is zero
|
|
|
|
flowRate.x,
|
|
|
|
flowRate.y,
|
|
|
|
bodyRate.x,
|
|
|
|
bodyRate.y,
|
|
|
|
optflow.quality(),
|
2016-11-25 21:14:57 -04:00
|
|
|
hagl, // ground distance (in meters) set to zero
|
|
|
|
flowRate.x,
|
|
|
|
flowRate.y);
|
2015-01-03 00:53:22 -04:00
|
|
|
}
|
|
|
|
#endif
|
2015-02-11 04:50:40 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
send AUTOPILOT_VERSION packet
|
|
|
|
*/
|
2017-09-05 02:58:32 -03:00
|
|
|
void GCS_MAVLINK::send_autopilot_version() const
|
2015-02-11 04:50:40 -04:00
|
|
|
{
|
2017-09-05 02:58:32 -03:00
|
|
|
uint32_t flight_sw_version;
|
2015-02-11 04:50:40 -04:00
|
|
|
uint32_t middleware_sw_version = 0;
|
|
|
|
uint32_t os_sw_version = 0;
|
|
|
|
uint32_t board_version = 0;
|
2018-01-09 17:38:14 -04:00
|
|
|
char flight_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN]{};
|
|
|
|
char middleware_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN]{};
|
|
|
|
char os_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN]{};
|
2015-02-11 04:50:40 -04:00
|
|
|
uint16_t vendor_id = 0;
|
|
|
|
uint16_t product_id = 0;
|
|
|
|
uint64_t uid = 0;
|
2018-01-09 17:38:14 -04:00
|
|
|
uint8_t uid2[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN] = {0};
|
2017-09-05 02:58:32 -03:00
|
|
|
const AP_FWVersion &version = get_fwver();
|
|
|
|
|
|
|
|
flight_sw_version = version.major << (8 * 3) | \
|
|
|
|
version.minor << (8 * 2) | \
|
|
|
|
version.patch << (8 * 1) | \
|
|
|
|
(uint32_t)(version.fw_type) << (8 * 0);
|
|
|
|
|
|
|
|
if (version.fw_hash_str) {
|
|
|
|
strncpy(flight_custom_version, version.fw_hash_str, sizeof(flight_custom_version) - 1);
|
|
|
|
flight_custom_version[sizeof(flight_custom_version) - 1] = '\0';
|
|
|
|
}
|
|
|
|
|
|
|
|
if (version.middleware_hash_str) {
|
|
|
|
strncpy(middleware_custom_version, version.middleware_hash_str, sizeof(middleware_custom_version) - 1);
|
|
|
|
middleware_custom_version[sizeof(middleware_custom_version) - 1] = '\0';
|
|
|
|
}
|
|
|
|
|
|
|
|
if (version.os_hash_str) {
|
|
|
|
strncpy(os_custom_version, version.os_hash_str, sizeof(os_custom_version) - 1);
|
|
|
|
os_custom_version[sizeof(os_custom_version) - 1] = '\0';
|
|
|
|
}
|
2015-02-11 04:50:40 -04:00
|
|
|
|
|
|
|
mavlink_msg_autopilot_version_send(
|
|
|
|
chan,
|
2015-07-30 03:41:18 -03:00
|
|
|
hal.util->get_capabilities(),
|
2015-02-11 04:50:40 -04:00
|
|
|
flight_sw_version,
|
|
|
|
middleware_sw_version,
|
|
|
|
os_sw_version,
|
|
|
|
board_version,
|
2017-09-05 02:58:32 -03:00
|
|
|
(uint8_t *)flight_custom_version,
|
|
|
|
(uint8_t *)middleware_custom_version,
|
|
|
|
(uint8_t *)os_custom_version,
|
2015-02-11 04:50:40 -04:00
|
|
|
vendor_id,
|
|
|
|
product_id,
|
2018-01-09 06:09:49 -04:00
|
|
|
uid,
|
|
|
|
uid2
|
2015-02-11 04:50:40 -04:00
|
|
|
);
|
|
|
|
}
|
|
|
|
|
2015-04-05 12:24:05 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
send LOCAL_POSITION_NED message
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::send_local_position(const AP_AHRS &ahrs) const
|
|
|
|
{
|
|
|
|
Vector3f local_position, velocity;
|
2017-01-30 15:08:07 -04:00
|
|
|
if (!ahrs.get_relative_position_NED_home(local_position) ||
|
2015-04-05 12:24:05 -03:00
|
|
|
!ahrs.get_velocity_NED(velocity)) {
|
|
|
|
// we don't know the position and velocity
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_msg_local_position_ned_send(
|
|
|
|
chan,
|
2015-11-19 23:15:38 -04:00
|
|
|
AP_HAL::millis(),
|
2015-04-05 12:24:05 -03:00
|
|
|
local_position.x,
|
|
|
|
local_position.y,
|
|
|
|
local_position.z,
|
|
|
|
velocity.x,
|
|
|
|
velocity.y,
|
|
|
|
velocity.z);
|
|
|
|
}
|
2015-06-12 03:35:31 -03:00
|
|
|
|
|
|
|
/*
|
2017-01-05 14:07:14 -04:00
|
|
|
send VIBRATION message
|
2015-06-12 03:35:31 -03:00
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::send_vibration(const AP_InertialSensor &ins) const
|
|
|
|
{
|
|
|
|
Vector3f vibration = ins.get_vibration_levels();
|
|
|
|
|
|
|
|
mavlink_msg_vibration_send(
|
|
|
|
chan,
|
2015-11-19 23:15:38 -04:00
|
|
|
AP_HAL::micros64(),
|
2015-06-12 03:35:31 -03:00
|
|
|
vibration.x,
|
|
|
|
vibration.y,
|
|
|
|
vibration.z,
|
|
|
|
ins.get_accel_clip_count(0),
|
|
|
|
ins.get_accel_clip_count(1),
|
|
|
|
ins.get_accel_clip_count(2));
|
|
|
|
}
|
2015-10-02 05:55:57 -03:00
|
|
|
|
|
|
|
void GCS_MAVLINK::send_home(const Location &home) const
|
|
|
|
{
|
2016-04-05 01:09:47 -03:00
|
|
|
if (HAVE_PAYLOAD_SPACE(chan, HOME_POSITION)) {
|
2015-10-02 05:55:57 -03:00
|
|
|
const float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};
|
|
|
|
mavlink_msg_home_position_send(
|
|
|
|
chan,
|
|
|
|
home.lat,
|
|
|
|
home.lng,
|
2016-04-15 16:32:25 -03:00
|
|
|
home.alt * 10,
|
2015-10-02 05:55:57 -03:00
|
|
|
0.0f, 0.0f, 0.0f,
|
|
|
|
q,
|
2017-09-22 05:17:20 -03:00
|
|
|
0.0f, 0.0f, 0.0f,
|
|
|
|
AP_HAL::micros64());
|
2015-10-02 05:55:57 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-09-17 22:35:12 -03:00
|
|
|
void GCS_MAVLINK::send_ekf_origin(const Location &ekf_origin) const
|
|
|
|
{
|
|
|
|
if (HAVE_PAYLOAD_SPACE(chan, GPS_GLOBAL_ORIGIN)) {
|
|
|
|
mavlink_msg_gps_global_origin_send(
|
|
|
|
chan,
|
|
|
|
ekf_origin.lat,
|
|
|
|
ekf_origin.lng,
|
2017-09-22 05:17:20 -03:00
|
|
|
ekf_origin.alt * 10,
|
|
|
|
AP_HAL::micros64());
|
2017-09-17 22:35:12 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-05-16 19:36:49 -03:00
|
|
|
/*
|
|
|
|
wrapper for sending heartbeat
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
|
|
|
|
{
|
|
|
|
mavlink_msg_heartbeat_send(
|
|
|
|
chan,
|
|
|
|
type,
|
|
|
|
MAV_AUTOPILOT_ARDUPILOTMEGA,
|
|
|
|
base_mode,
|
|
|
|
custom_mode,
|
|
|
|
system_status);
|
|
|
|
}
|
2016-05-28 10:02:38 -03:00
|
|
|
|
|
|
|
float GCS_MAVLINK::adjust_rate_for_stream_trigger(enum streams stream_num)
|
|
|
|
{
|
|
|
|
// send at a much lower rate while handling waypoints and
|
|
|
|
// parameter sends
|
|
|
|
if ((stream_num != STREAM_PARAMS) &&
|
2016-10-30 02:24:21 -03:00
|
|
|
(waypoint_receiving || _queued_parameter != nullptr)) {
|
2016-05-28 10:02:38 -03:00
|
|
|
return 0.25f;
|
|
|
|
}
|
|
|
|
|
|
|
|
return 1.0f;
|
|
|
|
}
|
2016-05-29 20:54:11 -03:00
|
|
|
|
|
|
|
// are we still delaying telemetry to try to avoid Xbee bricking?
|
2017-07-12 05:11:41 -03:00
|
|
|
bool GCS_MAVLINK::telemetry_delayed() const
|
2016-05-29 20:54:11 -03:00
|
|
|
{
|
|
|
|
uint32_t tnow = AP_HAL::millis() >> 10;
|
|
|
|
if (tnow > telem_delay()) {
|
|
|
|
return false;
|
|
|
|
}
|
2017-07-12 05:11:41 -03:00
|
|
|
if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
|
2016-05-29 20:54:11 -03:00
|
|
|
// this is USB telemetry, so won't be an Xbee
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// we're either on the 2nd UART, or no USB cable is connected
|
|
|
|
// we need to delay telemetry by the TELEM_DELAY time
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-07-15 07:04:19 -03:00
|
|
|
/*
|
|
|
|
send SERVO_OUTPUT_RAW
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::send_servo_output_raw(bool hil)
|
|
|
|
{
|
|
|
|
uint16_t values[16] {};
|
|
|
|
if (hil) {
|
|
|
|
for (uint8_t i=0; i<16; i++) {
|
2017-01-05 01:13:25 -04:00
|
|
|
values[i] = SRV_Channels::srv_channel(i)->get_output_pwm();
|
2016-07-15 07:04:19 -03:00
|
|
|
}
|
|
|
|
} else {
|
|
|
|
hal.rcout->read(values, 16);
|
|
|
|
}
|
|
|
|
for (uint8_t i=0; i<16; i++) {
|
|
|
|
if (values[i] == 65535) {
|
|
|
|
values[i] = 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
mavlink_msg_servo_output_raw_send(
|
|
|
|
chan,
|
|
|
|
AP_HAL::micros(),
|
|
|
|
0, // port
|
|
|
|
values[0], values[1], values[2], values[3],
|
|
|
|
values[4], values[5], values[6], values[7],
|
|
|
|
values[8], values[9], values[10], values[11],
|
|
|
|
values[12], values[13], values[14], values[15]);
|
|
|
|
}
|
2017-04-29 01:11:11 -03:00
|
|
|
|
|
|
|
|
2016-05-11 03:19:15 -03:00
|
|
|
void GCS_MAVLINK::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour)
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
|
|
|
|
if ((1U<<i) & mavlink_active) {
|
|
|
|
mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
|
|
|
|
if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_COLLISION) {
|
|
|
|
mavlink_msg_collision_send(
|
|
|
|
chan,
|
|
|
|
MAV_COLLISION_SRC_ADSB,
|
|
|
|
threat.src_id,
|
|
|
|
behaviour,
|
|
|
|
threat.threat_level,
|
|
|
|
threat.time_to_closest_approach,
|
|
|
|
threat.closest_approach_z,
|
|
|
|
threat.closest_approach_xy
|
|
|
|
);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2016-08-11 00:17:32 -03:00
|
|
|
|
2017-05-29 18:03:10 -03:00
|
|
|
void GCS_MAVLINK::send_accelcal_vehicle_position(uint32_t position)
|
2016-11-12 05:45:36 -04:00
|
|
|
{
|
|
|
|
if (HAVE_PAYLOAD_SPACE(chan, COMMAND_LONG)) {
|
|
|
|
mavlink_msg_command_long_send(
|
|
|
|
chan,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
MAV_CMD_ACCELCAL_VEHICLE_POS,
|
|
|
|
0,
|
|
|
|
(float) position,
|
|
|
|
0, 0, 0, 0, 0, 0);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-08-11 00:17:32 -03:00
|
|
|
/*
|
|
|
|
handle a MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command
|
|
|
|
|
|
|
|
Optionally disable PX4IO overrides. This is done for quadplanes to
|
|
|
|
prevent the mixer running while rebooting which can start the VTOL
|
|
|
|
motors. That can be dangerous when a preflight reboot is done with
|
|
|
|
the pilot close to the aircraft and can also damage the aircraft
|
|
|
|
*/
|
2017-11-27 02:15:38 -04:00
|
|
|
MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides)
|
2016-08-11 00:17:32 -03:00
|
|
|
{
|
|
|
|
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
|
|
|
|
if (disable_overrides) {
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
|
|
// disable overrides while rebooting
|
|
|
|
int px4io_fd = open("/dev/px4io", 0);
|
|
|
|
if (px4io_fd >= 0) {
|
|
|
|
// disable OVERRIDES so we don't run the mixer while
|
|
|
|
// rebooting
|
|
|
|
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_OK, 0) != 0) {
|
|
|
|
hal.console->printf("SET_OVERRIDE_OK failed\n");
|
|
|
|
}
|
|
|
|
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 0) != 0) {
|
|
|
|
hal.console->printf("SET_OVERRIDE_IMMEDIATE failed\n");
|
|
|
|
}
|
|
|
|
close(px4io_fd);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
// force safety on
|
|
|
|
hal.rcout->force_safety_on();
|
|
|
|
hal.rcout->force_safety_no_wait();
|
|
|
|
hal.scheduler->delay(200);
|
|
|
|
|
|
|
|
// when packet.param1 == 3 we reboot to hold in bootloader
|
|
|
|
bool hold_in_bootloader = is_equal(packet.param1,3.0f);
|
|
|
|
hal.scheduler->reboot(hold_in_bootloader);
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
2016-10-15 05:51:17 -03:00
|
|
|
|
2017-07-25 03:36:53 -03:00
|
|
|
/*
|
|
|
|
handle a flight termination request
|
|
|
|
*/
|
|
|
|
MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
AP_AdvancedFailsafe *failsafe = get_advanced_failsafe();
|
|
|
|
if (failsafe == nullptr) {
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool should_terminate = packet.param1 > 0.5f;
|
|
|
|
|
|
|
|
if (failsafe->gcs_terminate(should_terminate)) {
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
2016-10-15 05:51:17 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
handle a R/C bind request (for spektrum)
|
|
|
|
*/
|
2017-07-16 20:49:21 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK::handle_rc_bind(const mavlink_command_long_t &packet)
|
2016-10-15 05:51:17 -03:00
|
|
|
{
|
|
|
|
// initiate bind procedure. We accept the DSM type from either
|
|
|
|
// param1 or param2 due to a past mixup with what parameter is the
|
|
|
|
// right one
|
|
|
|
if (!hal.rcin->rc_bind(packet.param2>0?packet.param2:packet.param1)) {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
2016-11-06 20:03:11 -04:00
|
|
|
|
2017-03-29 03:47:32 -03:00
|
|
|
/*
|
|
|
|
return a timesync request
|
|
|
|
Sends back ts1 as received, and tc1 is the local timestamp in usec
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_timesync(mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
// decode incoming timesync message
|
|
|
|
mavlink_timesync_t tsync;
|
|
|
|
mavlink_msg_timesync_decode(msg, &tsync);
|
|
|
|
|
|
|
|
// ignore messages in which tc1 field (timestamp 1) has already been filled in
|
|
|
|
if (tsync.tc1 != 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-03-29 19:45:04 -03:00
|
|
|
// create new timesync struct with tc1 field as system time in nanoseconds
|
2017-03-29 03:47:32 -03:00
|
|
|
mavlink_timesync_t rsync;
|
2017-03-29 19:45:04 -03:00
|
|
|
rsync.tc1 = AP_HAL::micros64() * 1000;
|
2017-03-29 03:47:32 -03:00
|
|
|
rsync.ts1 = tsync.ts1;
|
|
|
|
|
|
|
|
// respond with a timesync message
|
|
|
|
mavlink_msg_timesync_send(
|
|
|
|
chan,
|
|
|
|
rsync.tc1,
|
|
|
|
rsync.ts1
|
|
|
|
);
|
|
|
|
}
|
|
|
|
|
2017-07-12 04:21:15 -03:00
|
|
|
void GCS_MAVLINK::handle_statustext(mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
DataFlash_Class *df = DataFlash_Class::instance();
|
|
|
|
if (df == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
2017-08-10 02:22:34 -03:00
|
|
|
|
2017-07-12 04:21:15 -03:00
|
|
|
mavlink_statustext_t packet;
|
|
|
|
mavlink_msg_statustext_decode(msg, &packet);
|
2017-08-10 02:22:34 -03:00
|
|
|
const uint8_t max_prefix_len = 20;
|
|
|
|
const uint8_t text_len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1+max_prefix_len;
|
|
|
|
char text[text_len] = { 'G','C','S',':'};
|
|
|
|
uint8_t offset = strlen(text);
|
|
|
|
|
|
|
|
if (msg->sysid != sysid_my_gcs()) {
|
|
|
|
offset = hal.util->snprintf(text,
|
|
|
|
max_prefix_len,
|
|
|
|
"SRC=%u/%u:",
|
|
|
|
msg->sysid,
|
|
|
|
msg->compid);
|
|
|
|
}
|
|
|
|
|
|
|
|
memcpy(&text[offset], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
|
|
|
|
|
2017-07-12 04:21:15 -03:00
|
|
|
df->Log_Write_Message(text);
|
|
|
|
}
|
2017-03-29 03:47:32 -03:00
|
|
|
|
2017-07-25 04:01:47 -03:00
|
|
|
|
|
|
|
void GCS_MAVLINK::handle_common_gps_message(mavlink_message_t *msg)
|
|
|
|
{
|
2017-10-25 01:32:35 -03:00
|
|
|
AP::gps().handle_msg(msg);
|
2017-07-25 04:01:47 -03:00
|
|
|
}
|
|
|
|
|
2017-07-26 02:48:01 -03:00
|
|
|
|
|
|
|
void GCS_MAVLINK::handle_common_camera_message(const mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
AP_Camera *camera = get_camera();
|
|
|
|
if (camera == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
switch (msg->msgid) {
|
|
|
|
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE: // MAV ID: 202
|
|
|
|
//deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
|
|
|
break;
|
|
|
|
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
|
|
|
|
//deprecated. Use MAV_CMD_DO_DIGICAM_CONTROL
|
|
|
|
camera->control_msg(msg);
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
AP_Camera *camera = get_camera();
|
|
|
|
if (camera == nullptr) {
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
|
|
|
|
MAV_RESULT result = MAV_RESULT_FAILED;
|
|
|
|
switch (packet.command) {
|
|
|
|
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
|
|
|
camera->configure(packet.param1,
|
|
|
|
packet.param2,
|
|
|
|
packet.param3,
|
|
|
|
packet.param4,
|
|
|
|
packet.param5,
|
|
|
|
packet.param6,
|
|
|
|
packet.param7);
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
break;
|
|
|
|
case MAV_CMD_DO_DIGICAM_CONTROL:
|
|
|
|
camera->control(packet.param1,
|
|
|
|
packet.param2,
|
|
|
|
packet.param3,
|
|
|
|
packet.param4,
|
|
|
|
packet.param5,
|
|
|
|
packet.param6);
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
break;
|
|
|
|
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
|
|
|
camera->set_trigger_distance(packet.param1);
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
result = MAV_RESULT_UNSUPPORTED;
|
2017-09-19 21:08:30 -03:00
|
|
|
break;
|
2017-07-26 02:48:01 -03:00
|
|
|
}
|
|
|
|
return result;
|
|
|
|
}
|
|
|
|
|
2017-09-18 23:30:32 -03:00
|
|
|
void GCS_MAVLINK::handle_set_gps_global_origin(const mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
mavlink_set_gps_global_origin_t packet;
|
|
|
|
mavlink_msg_set_gps_global_origin_decode(msg, &packet);
|
|
|
|
|
|
|
|
// sanity check location
|
|
|
|
if (!check_latlng(packet.latitude, packet.longitude)) {
|
|
|
|
// silently drop the request
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
Location ekf_origin {};
|
|
|
|
ekf_origin.lat = packet.latitude;
|
|
|
|
ekf_origin.lng = packet.longitude;
|
|
|
|
ekf_origin.alt = packet.altitude / 10;
|
|
|
|
set_ekf_origin(ekf_origin);
|
|
|
|
}
|
|
|
|
|
2018-01-18 02:32:22 -04:00
|
|
|
/*
|
|
|
|
handle a DATA96 message
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_data_packet(mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
#ifdef HAL_RCINPUT_WITH_AP_RADIO
|
|
|
|
mavlink_data96_t m;
|
|
|
|
mavlink_msg_data96_decode(msg, &m);
|
|
|
|
switch (m.type) {
|
|
|
|
case 42:
|
|
|
|
case 43: {
|
|
|
|
// pass to AP_Radio (for firmware upload and playing test tunes)
|
|
|
|
AP_Radio *radio = AP_Radio::instance();
|
|
|
|
if (radio != nullptr) {
|
|
|
|
radio->handle_data_packet(chan, m);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
default:
|
|
|
|
// unknown
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2016-11-06 20:03:11 -04:00
|
|
|
/*
|
|
|
|
handle messages which don't require vehicle specific data
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
switch (msg->msgid) {
|
|
|
|
case MAVLINK_MSG_ID_SETUP_SIGNING:
|
|
|
|
handle_setup_signing(msg);
|
|
|
|
break;
|
2017-08-19 07:17:09 -03:00
|
|
|
|
2017-08-19 07:26:10 -03:00
|
|
|
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
|
|
|
/* fall through */
|
2017-08-19 07:22:58 -03:00
|
|
|
case MAVLINK_MSG_ID_PARAM_SET:
|
|
|
|
/* fall through */
|
2016-11-06 20:03:11 -04:00
|
|
|
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
|
2017-08-19 07:17:09 -03:00
|
|
|
handle_common_param_message(msg);
|
2016-11-06 20:03:11 -04:00
|
|
|
break;
|
2017-08-19 07:17:09 -03:00
|
|
|
|
2017-09-18 23:30:32 -03:00
|
|
|
case MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN:
|
|
|
|
handle_set_gps_global_origin(msg);
|
|
|
|
break;
|
|
|
|
|
2016-11-06 21:42:47 -04:00
|
|
|
case MAVLINK_MSG_ID_DEVICE_OP_READ:
|
|
|
|
handle_device_op_read(msg);
|
|
|
|
break;
|
|
|
|
case MAVLINK_MSG_ID_DEVICE_OP_WRITE:
|
|
|
|
handle_device_op_write(msg);
|
|
|
|
break;
|
2017-03-29 03:47:32 -03:00
|
|
|
case MAVLINK_MSG_ID_TIMESYNC:
|
|
|
|
handle_timesync(msg);
|
|
|
|
break;
|
2017-06-15 03:09:02 -03:00
|
|
|
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_LOG_ERASE:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_LOG_REQUEST_END:
|
|
|
|
/* fall through */
|
2017-06-15 00:27:31 -03:00
|
|
|
case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
|
2017-06-15 03:09:02 -03:00
|
|
|
DataFlash_Class::instance()->handle_mavlink_msg(*this, msg);
|
2017-06-15 00:27:31 -03:00
|
|
|
break;
|
2017-07-07 23:51:37 -03:00
|
|
|
|
|
|
|
|
2017-07-26 02:48:01 -03:00
|
|
|
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
|
|
|
|
/* fall through */
|
|
|
|
handle_common_camera_message(msg);
|
|
|
|
break;
|
|
|
|
|
2017-08-11 02:52:09 -03:00
|
|
|
case MAVLINK_MSG_ID_SET_MODE:
|
|
|
|
handle_set_mode(msg);
|
|
|
|
break;
|
|
|
|
|
2017-08-18 20:07:42 -03:00
|
|
|
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
|
|
|
|
handle_send_autopilot_version(msg);
|
|
|
|
break;
|
|
|
|
|
2017-07-15 03:32:25 -03:00
|
|
|
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
|
|
|
|
/* fall through */
|
2017-07-07 23:51:37 -03:00
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_MISSION_COUNT:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ACK:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
|
|
|
|
handle_common_mission_message(msg);
|
|
|
|
break;
|
2017-07-25 04:01:47 -03:00
|
|
|
|
2017-08-17 07:04:42 -03:00
|
|
|
case MAVLINK_MSG_ID_SERIAL_CONTROL:
|
|
|
|
handle_serial_control(msg);
|
|
|
|
break;
|
|
|
|
|
2017-07-25 04:01:47 -03:00
|
|
|
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_GPS_INPUT:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_HIL_GPS:
|
2017-07-25 04:58:25 -03:00
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_GPS_INJECT_DATA:
|
2017-07-25 04:01:47 -03:00
|
|
|
handle_common_gps_message(msg);
|
|
|
|
break;
|
2017-07-12 04:21:15 -03:00
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_STATUSTEXT:
|
|
|
|
handle_statustext(msg);
|
|
|
|
break;
|
2017-07-12 21:20:45 -03:00
|
|
|
|
2017-08-17 00:43:45 -03:00
|
|
|
case MAVLINK_MSG_ID_LED_CONTROL:
|
|
|
|
// send message to Notify
|
|
|
|
AP_Notify::handle_led_control(msg);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_PLAY_TUNE:
|
|
|
|
// send message to Notify
|
|
|
|
AP_Notify::handle_play_tune(msg);
|
|
|
|
break;
|
|
|
|
|
2017-07-12 21:20:45 -03:00
|
|
|
case MAVLINK_MSG_ID_RALLY_POINT:
|
|
|
|
/* fall through */
|
|
|
|
case MAVLINK_MSG_ID_RALLY_FETCH_POINT:
|
|
|
|
handle_common_rally_message(msg);
|
|
|
|
break;
|
2018-01-18 02:32:22 -04:00
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_DATA96:
|
|
|
|
handle_data_packet(msg);
|
|
|
|
break;
|
2017-07-07 23:51:37 -03:00
|
|
|
}
|
2017-07-12 04:21:15 -03:00
|
|
|
|
2017-07-07 23:51:37 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void GCS_MAVLINK::handle_common_mission_message(mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
AP_Mission *_mission = get_mission();
|
|
|
|
if (_mission == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
switch (msg->msgid) {
|
|
|
|
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: // MAV ID: 38
|
|
|
|
{
|
|
|
|
handle_mission_write_partial_list(*_mission, msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// GCS has sent us a mission item, store to EEPROM
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM: // MAV ID: 39
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
|
|
|
|
{
|
|
|
|
if (handle_mission_item(msg, *_mission)) {
|
|
|
|
DataFlash_Class::instance()->Log_Write_EntireMission(*_mission);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// read an individual command from EEPROM and send it to the GCS
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST: // MAV ID: 40, 51
|
|
|
|
{
|
|
|
|
handle_mission_request(*_mission, msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_SET_CURRENT: // MAV ID: 41
|
|
|
|
{
|
|
|
|
handle_mission_set_current(*_mission, msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// GCS request the full list of commands, we return just the number and leave the GCS to then request each command individually
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: // MAV ID: 43
|
|
|
|
{
|
|
|
|
handle_mission_request_list(*_mission, msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// GCS provides the full number of commands it wishes to upload
|
|
|
|
// individual commands will then be sent from the GCS using the MAVLINK_MSG_ID_MISSION_ITEM message
|
|
|
|
case MAVLINK_MSG_ID_MISSION_COUNT: // MAV ID: 44
|
|
|
|
{
|
|
|
|
handle_mission_count(*_mission, msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: // MAV ID: 45
|
|
|
|
{
|
|
|
|
handle_mission_clear_all(*_mission, msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ACK:
|
|
|
|
/* not used */
|
|
|
|
break;
|
2016-11-06 20:03:11 -04:00
|
|
|
}
|
|
|
|
}
|
2016-05-30 07:05:00 -03:00
|
|
|
|
2017-08-18 20:07:42 -03:00
|
|
|
void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t *msg)
|
|
|
|
{
|
2017-09-05 02:58:32 -03:00
|
|
|
send_autopilot_version();
|
2017-08-18 20:07:42 -03:00
|
|
|
}
|
|
|
|
|
2017-08-19 08:23:19 -03:00
|
|
|
void GCS_MAVLINK::send_banner()
|
|
|
|
{
|
|
|
|
// mark the firmware version in the tlog
|
|
|
|
const AP_FWVersion &fwver = get_fwver();
|
|
|
|
send_text(MAV_SEVERITY_INFO, fwver.fw_string);
|
|
|
|
|
2017-09-19 14:43:55 -03:00
|
|
|
if (fwver.middleware_hash_str && fwver.os_hash_str) {
|
|
|
|
send_text(MAV_SEVERITY_INFO, "PX4: %s NuttX: %s",
|
|
|
|
fwver.middleware_hash_str, fwver.os_hash_str);
|
|
|
|
}
|
2017-08-19 08:23:19 -03:00
|
|
|
|
|
|
|
// send system ID if we can
|
|
|
|
char sysid[40];
|
|
|
|
if (hal.util->get_system_id(sysid)) {
|
|
|
|
send_text(MAV_SEVERITY_INFO, sysid);
|
|
|
|
}
|
|
|
|
}
|
2017-08-18 20:07:42 -03:00
|
|
|
|
|
|
|
|
2017-07-16 22:04:32 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
Compass *compass = get_compass();
|
|
|
|
if (compass == nullptr) {
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t compassNumber = -1;
|
|
|
|
if (is_equal(packet.param1, 2.0f)) {
|
|
|
|
compassNumber = 0;
|
|
|
|
} else if (is_equal(packet.param1, 5.0f)) {
|
|
|
|
compassNumber = 1;
|
|
|
|
} else if (is_equal(packet.param1, 6.0f)) {
|
|
|
|
compassNumber = 2;
|
|
|
|
}
|
|
|
|
if (compassNumber == (uint8_t) -1) {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
compass->set_and_save_offsets(compassNumber, packet.param2, packet.param3, packet.param4);
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
|
2017-07-16 21:46:54 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
Compass *compass = get_compass();
|
|
|
|
if (compass == nullptr) {
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
return compass->handle_mag_cal_command(packet);
|
|
|
|
}
|
|
|
|
|
2017-08-18 20:07:42 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
if (!is_equal(packet.param1,1.0f)) {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
|
2017-09-05 02:58:32 -03:00
|
|
|
send_autopilot_version();
|
|
|
|
|
2017-08-18 20:07:42 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
|
2017-08-19 11:29:01 -03:00
|
|
|
|
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_do_send_banner(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
send_banner();
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
|
2017-09-16 08:50:59 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_do_set_mode(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
const MAV_MODE base_mode = (MAV_MODE)packet.param1;
|
|
|
|
const uint32_t custom_mode = (uint32_t)packet.param2;
|
|
|
|
|
|
|
|
return _set_mode_common(base_mode, custom_mode);
|
|
|
|
}
|
|
|
|
|
2017-07-13 22:43:30 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
MAV_RESULT result = MAV_RESULT_FAILED;
|
|
|
|
|
|
|
|
switch (packet.command) {
|
2017-07-13 23:44:21 -03:00
|
|
|
|
2017-09-16 08:50:59 -03:00
|
|
|
case MAV_CMD_DO_SET_MODE:
|
|
|
|
result = handle_command_do_set_mode(packet);
|
|
|
|
break;
|
|
|
|
|
2017-08-19 11:29:01 -03:00
|
|
|
case MAV_CMD_DO_SEND_BANNER:
|
|
|
|
result = handle_command_do_send_banner(packet);
|
|
|
|
break;
|
|
|
|
|
2017-07-16 21:46:54 -03:00
|
|
|
case MAV_CMD_DO_START_MAG_CAL:
|
|
|
|
case MAV_CMD_DO_ACCEPT_MAG_CAL:
|
|
|
|
case MAV_CMD_DO_CANCEL_MAG_CAL: {
|
|
|
|
result = handle_command_mag_cal(packet);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-07-16 20:49:21 -03:00
|
|
|
case MAV_CMD_START_RX_PAIR:
|
|
|
|
result = handle_rc_bind(packet);
|
|
|
|
break;
|
|
|
|
|
2017-07-26 02:48:01 -03:00
|
|
|
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
|
|
|
/* fall through */
|
|
|
|
case MAV_CMD_DO_DIGICAM_CONTROL:
|
|
|
|
/* fall through */
|
|
|
|
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
|
|
|
result = handle_command_camera(packet);
|
|
|
|
break;
|
|
|
|
|
2017-08-18 20:07:42 -03:00
|
|
|
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
|
|
|
|
result = handle_command_request_autopilot_capabilities(packet);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-07-16 22:04:32 -03:00
|
|
|
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: {
|
|
|
|
result = handle_command_preflight_set_sensor_offsets(packet);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2018-02-14 14:19:46 -04:00
|
|
|
case MAV_CMD_PREFLIGHT_STORAGE:
|
|
|
|
if (is_equal(packet.param1, 2.0f)) {
|
|
|
|
AP_Param::erase_all();
|
|
|
|
send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board");
|
|
|
|
result= MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2017-07-13 23:44:21 -03:00
|
|
|
case MAV_CMD_DO_SET_SERVO:
|
|
|
|
/* fall through */
|
|
|
|
case MAV_CMD_DO_REPEAT_SERVO:
|
|
|
|
/* fall through */
|
|
|
|
case MAV_CMD_DO_SET_RELAY:
|
|
|
|
/* fall through */
|
|
|
|
case MAV_CMD_DO_REPEAT_RELAY:
|
|
|
|
/* fall through */
|
|
|
|
result = handle_servorelay_message(packet);
|
|
|
|
break;
|
|
|
|
|
2017-07-25 03:36:53 -03:00
|
|
|
case MAV_CMD_DO_FLIGHTTERMINATION:
|
|
|
|
result = handle_flight_termination(packet);
|
|
|
|
break;
|
|
|
|
|
2017-07-13 22:43:30 -03:00
|
|
|
default:
|
|
|
|
result = MAV_RESULT_UNSUPPORTED;
|
2017-09-19 21:08:30 -03:00
|
|
|
break;
|
2017-07-13 22:43:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
return result;
|
|
|
|
}
|
|
|
|
|
2017-07-17 20:53:41 -03:00
|
|
|
bool GCS_MAVLINK::try_send_compass_message(const enum ap_message id)
|
|
|
|
{
|
|
|
|
Compass *compass = get_compass();
|
|
|
|
if (compass == nullptr) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
bool ret = true;
|
|
|
|
switch (id) {
|
|
|
|
case MSG_MAG_CAL_PROGRESS:
|
|
|
|
compass->send_mag_cal_progress(chan);
|
|
|
|
ret = true;;
|
|
|
|
break;
|
|
|
|
case MSG_MAG_CAL_REPORT:
|
|
|
|
compass->send_mag_cal_report(chan);
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2017-07-18 05:55:06 -03:00
|
|
|
bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
|
|
|
|
{
|
|
|
|
AP_Mission *mission = get_mission();
|
|
|
|
if (mission == nullptr) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool ret = true;
|
|
|
|
switch (id) {
|
|
|
|
case MSG_CURRENT_WAYPOINT:
|
|
|
|
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
|
|
|
|
mavlink_msg_mission_current_send(chan, mission->get_current_nav_index());
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
case MSG_MISSION_ITEM_REACHED:
|
|
|
|
CHECK_PAYLOAD_SIZE(MISSION_ITEM_REACHED);
|
|
|
|
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
case MSG_NEXT_WAYPOINT:
|
|
|
|
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
|
|
|
|
queued_waypoint_send();
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2017-07-18 08:50:23 -03:00
|
|
|
void GCS_MAVLINK::send_hwstatus()
|
|
|
|
{
|
|
|
|
mavlink_msg_hwstatus_send(
|
|
|
|
chan,
|
|
|
|
hal.analogin->board_voltage()*1000,
|
|
|
|
0);
|
|
|
|
}
|
2017-07-18 05:55:06 -03:00
|
|
|
|
2017-08-04 05:37:30 -03:00
|
|
|
bool GCS_MAVLINK::try_send_gps_message(const enum ap_message id)
|
|
|
|
{
|
|
|
|
bool ret = true;
|
|
|
|
switch(id) {
|
|
|
|
case MSG_SYSTEM_TIME:
|
|
|
|
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
|
2017-10-25 01:32:35 -03:00
|
|
|
send_system_time();
|
2017-08-04 05:37:30 -03:00
|
|
|
ret = true;
|
|
|
|
break;
|
2017-08-04 05:40:09 -03:00
|
|
|
case MSG_GPS_RAW:
|
|
|
|
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
|
2017-10-25 01:32:35 -03:00
|
|
|
AP::gps().send_mavlink_gps_raw(chan);
|
2017-08-08 07:01:26 -03:00
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
case MSG_GPS_RTK:
|
|
|
|
CHECK_PAYLOAD_SIZE(GPS_RTK);
|
2017-10-25 01:32:35 -03:00
|
|
|
AP::gps().send_mavlink_gps_rtk(chan, 0);
|
2017-08-08 07:01:26 -03:00
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
case MSG_GPS2_RAW:
|
|
|
|
CHECK_PAYLOAD_SIZE(GPS2_RAW);
|
2017-10-25 01:32:35 -03:00
|
|
|
AP::gps().send_mavlink_gps2_raw(chan);
|
2017-08-08 07:01:26 -03:00
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
case MSG_GPS2_RTK:
|
|
|
|
CHECK_PAYLOAD_SIZE(GPS2_RTK);
|
2017-10-25 01:32:35 -03:00
|
|
|
AP::gps().send_mavlink_gps_rtk(chan, 1);
|
2017-08-04 05:40:09 -03:00
|
|
|
ret = true;
|
|
|
|
break;
|
2017-08-04 05:37:30 -03:00
|
|
|
default:
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2017-08-04 05:22:39 -03:00
|
|
|
bool GCS_MAVLINK::try_send_camera_message(const enum ap_message id)
|
|
|
|
{
|
|
|
|
AP_Camera *camera = get_camera();
|
|
|
|
if (camera == nullptr) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool ret = true;
|
|
|
|
switch(id) {
|
|
|
|
case MSG_CAMERA_FEEDBACK:
|
|
|
|
CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
|
|
|
|
camera->send_feedback(chan);
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2017-07-17 20:53:41 -03:00
|
|
|
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|
|
|
{
|
|
|
|
if (telemetry_delayed()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool ret = true;
|
|
|
|
|
|
|
|
switch(id) {
|
|
|
|
|
2017-07-18 10:03:53 -03:00
|
|
|
case MSG_NEXT_PARAM:
|
|
|
|
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
|
|
|
|
queued_param_send();
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
|
2017-07-18 08:50:23 -03:00
|
|
|
case MSG_HWSTATUS:
|
|
|
|
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
|
|
|
send_hwstatus();
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
|
2017-07-18 05:55:06 -03:00
|
|
|
case MSG_CURRENT_WAYPOINT:
|
|
|
|
/* fall through */
|
|
|
|
case MSG_MISSION_ITEM_REACHED:
|
|
|
|
/* fall through */
|
|
|
|
case MSG_NEXT_WAYPOINT:
|
|
|
|
ret = try_send_mission_message(id);
|
|
|
|
break;
|
|
|
|
|
2017-07-17 20:53:41 -03:00
|
|
|
case MSG_MAG_CAL_PROGRESS:
|
|
|
|
/* fall through */
|
|
|
|
case MSG_MAG_CAL_REPORT:
|
|
|
|
ret = try_send_compass_message(id);
|
|
|
|
break;
|
|
|
|
|
2017-08-04 05:10:24 -03:00
|
|
|
case MSG_EXTENDED_STATUS2:
|
|
|
|
CHECK_PAYLOAD_SIZE(MEMINFO);
|
|
|
|
send_meminfo();
|
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
|
2017-08-04 05:22:39 -03:00
|
|
|
case MSG_CAMERA_FEEDBACK:
|
|
|
|
ret = try_send_camera_message(id);
|
|
|
|
break;
|
|
|
|
|
2017-08-04 05:40:09 -03:00
|
|
|
case MSG_GPS_RAW:
|
|
|
|
/* fall through */
|
2017-08-08 07:01:26 -03:00
|
|
|
case MSG_GPS_RTK:
|
|
|
|
/* fall through */
|
|
|
|
case MSG_GPS2_RAW:
|
|
|
|
/* fall through */
|
|
|
|
case MSG_GPS2_RTK:
|
|
|
|
/* fall through */
|
2017-08-04 05:37:30 -03:00
|
|
|
case MSG_SYSTEM_TIME:
|
|
|
|
ret = try_send_gps_message(id);
|
|
|
|
break;
|
2017-08-04 05:22:39 -03:00
|
|
|
|
2017-07-17 20:53:41 -03:00
|
|
|
default:
|
|
|
|
// try_send_message must always at some stage return true for
|
|
|
|
// a message, or we will attempt to infinitely retry the
|
|
|
|
// message as part of send_message.
|
|
|
|
// This message will be sent out at the same rate as the
|
|
|
|
// unknown message, so should be safe.
|
|
|
|
gcs().send_text(MAV_SEVERITY_DEBUG, "Sending unknown message (%u)", id);
|
2017-11-26 21:51:50 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
AP_HAL::panic("Sending unknown ap_message %u", id);
|
|
|
|
#endif
|
2017-07-17 20:53:41 -03:00
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2016-05-30 07:05:00 -03:00
|
|
|
GCS &gcs()
|
|
|
|
{
|
|
|
|
return *GCS::instance();
|
|
|
|
}
|