ardupilot/ArduSub/GCS_Mavlink.cpp

1299 lines
44 KiB
C++
Raw Normal View History

2016-01-14 15:30:56 -04:00
#include "Sub.h"
#include "GCS_Mavlink.h"
// default sensors are present and healthy: gyro, accelerometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control
2018-03-01 14:44:02 -04:00
#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS | MAV_SYS_STATUS_SENSOR_BATTERY)
void Sub::gcs_send_heartbeat()
{
2017-07-07 23:02:04 -03:00
gcs().send_message(MSG_HEARTBEAT);
}
void Sub::gcs_send_deferred()
{
2017-07-18 22:37:58 -03:00
gcs().retry_deferred();
}
/*
* !!NOTE!!
*
* the use of NOINLINE separate functions for each message type avoids
* a compiler bug in gcc that would cause it to use far more stack
* space than is needed. Without the NOINLINE we use the sum of the
* stack needed for each message type. Please be careful to follow the
* pattern below when adding any new messages
*/
MAV_TYPE GCS_MAVLINK_Sub::frame_type() const
{
return MAV_TYPE_SUBMARINE;
}
MAV_MODE GCS_MAVLINK_Sub::base_mode() const
{
2018-04-03 11:35:43 -03:00
uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
// work out the base_mode. This value is not very useful
// for APM, but we calculate it as best we can so a generic
// MAVLink enabled ground station can work out something about
// what the MAV is up to. The actual bit values are highly
// ambiguous for most of the APM flight modes. In practice, you
// only get useful information from the custom_mode, which maps to
// the APM flight mode and has a well defined meaning in the
// ArduPlane documentation
switch (sub.control_mode) {
case AUTO:
case GUIDED:
case CIRCLE:
case POSHOLD:
2018-04-03 11:35:43 -03:00
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
// APM does in any mode, as that is defined as "system finds its own goal
// positions", which APM does not currently do
break;
2016-04-18 01:38:21 -03:00
default:
break;
}
// all modes except INITIALISING have some form of manual
// override if stick mixing is enabled
2018-04-03 11:35:43 -03:00
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
if (sub.motors.armed()) {
2018-04-03 11:35:43 -03:00
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
}
// indicate we have set a custom mode
2018-04-03 11:35:43 -03:00
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
2018-04-03 11:35:43 -03:00
return (MAV_MODE)_base_mode;
}
uint32_t GCS_MAVLINK_Sub::custom_mode() const
{
return sub.control_mode;
}
MAV_STATE GCS_MAVLINK_Sub::system_status() const
{
// set system as critical if any failsafe have triggered
if (sub.any_failsafe_triggered()) {
return MAV_STATE_CRITICAL;
}
if (sub.motors.armed()) {
return MAV_STATE_ACTIVE;
}
return MAV_STATE_STANDBY;
}
2016-01-14 15:30:56 -04:00
NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
{
uint32_t control_sensors_present;
uint32_t control_sensors_enabled;
uint32_t control_sensors_health;
// default sensors present
control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT;
// first what sensors/controllers we have
if (g.compass_enabled) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present
}
if (ap.depth_sensor_present) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
if (gps.status() > AP_GPS::NO_GPS) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
}
#if OPTFLOW == ENABLED
if (optflow.enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif
// all present sensors enabled by default except altitude and position control and motors which we will set individually
control_sensors_enabled = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL &
~MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL &
2018-03-01 14:44:02 -04:00
~MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS & ~MAV_SYS_STATUS_SENSOR_BATTERY);
switch (control_mode) {
case ALT_HOLD:
case AUTO:
case GUIDED:
case CIRCLE:
2016-08-25 00:08:30 -03:00
case SURFACE:
case POSHOLD:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
break;
2016-04-18 01:38:21 -03:00
default:
break;
}
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
}
2018-03-01 14:44:02 -04:00
if (battery.num_instances() > 0) {
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY;
}
// default to all healthy except baro, compass, gps and receiver which we set individually
control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE |
MAV_SYS_STATUS_SENSOR_3D_MAG |
MAV_SYS_STATUS_SENSOR_GPS |
MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
if (sensor_health.depth) { // check the internal barometer only
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}
2017-09-21 23:54:26 -03:00
if (gps.is_healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
#if OPTFLOW == ENABLED
if (optflow.healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
}
#endif
2017-03-09 13:50:58 -04:00
if (!ins.get_gyro_health_all() || !ins.gyro_calibrated_ok_all()) {
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_GYRO;
}
if (!ins.get_accel_health_all()) {
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL;
}
if (ahrs.initialised() && !ahrs.healthy()) {
// AHRS subsystem is unhealthy
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}
2018-03-01 14:44:02 -04:00
if (!battery.healthy() || battery.has_failsafed()) {
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_BATTERY;
}
int16_t battery_current = -1;
int8_t battery_remaining = -1;
if (battery.has_current() && battery.healthy()) {
// percent remaining is not necessarily accurate at the moment
//battery_remaining = battery.capacity_remaining_pct();
battery_current = battery.current_amps() * 100;
}
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
switch (terrain.status()) {
case AP_Terrain::TerrainStatusDisabled:
break;
case AP_Terrain::TerrainStatusUnhealthy:
2017-02-10 13:46:54 -04:00
// To-Do: restore unhealthy terrain status reporting once terrain is used in Sub
//control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
//control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
//break;
case AP_Terrain::TerrainStatusOK:
control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
control_sensors_health |= MAV_SYS_STATUS_TERRAIN;
break;
}
#endif
#if RANGEFINDER_ENABLED == ENABLED
if (rangefinder_state.enabled) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
if (rangefinder.has_data_orient(ROTATION_PITCH_270)) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
}
}
#endif
if (!ap.initialised || ins.calibrating()) {
// while initialising the gyros and accels are not enabled
control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
}
mavlink_msg_sys_status_send(
chan,
control_sensors_present,
control_sensors_enabled,
control_sensors_health,
(uint16_t)(scheduler.load_average() * 1000),
battery.voltage() * 1000, // mV
battery_current, // in 10mA units
battery_remaining, // in %
0, // comm drops %,
0, // comm drops in pkts,
0, 0, 0, 0);
}
2016-01-14 15:30:56 -04:00
void NOINLINE Sub::send_nav_controller_output(mavlink_channel_t chan)
{
const Vector3f &targets = attitude_control.get_att_target_euler_cd();
mavlink_msg_nav_controller_output_send(
chan,
targets.x * 1.0e-2f,
targets.y * 1.0e-2f,
targets.z * 1.0e-2f,
wp_nav.get_wp_bearing_to_destination() * 1.0e-2f,
MIN(wp_nav.get_wp_distance_to_destination() * 1.0e-2f, UINT16_MAX),
pos_control.get_alt_error() * 1.0e-2f,
0,
0);
}
2018-01-30 22:59:06 -04:00
int16_t GCS_MAVLINK_Sub::vfr_hud_throttle() const
{
2018-01-30 22:59:06 -04:00
return (int16_t)(sub.motors.get_throttle() * 100);
}
/*
send RPM packet
*/
2016-11-25 18:58:31 -04:00
#if RPM_ENABLED == ENABLED
2016-01-14 15:30:56 -04:00
void NOINLINE Sub::send_rpm(mavlink_channel_t chan)
{
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
mavlink_msg_rpm_send(
chan,
rpm_sensor.get_rpm(0),
rpm_sensor.get_rpm(1));
}
}
2016-11-25 18:58:31 -04:00
#endif
2017-01-13 15:51:48 -04:00
// Work around to get temperature sensor data out
void GCS_MAVLINK_Sub::send_scaled_pressure3()
{
if (!sub.celsius.healthy()) {
return;
}
mavlink_msg_scaled_pressure3_send(
chan,
AP_HAL::millis(),
0,
0,
sub.celsius.temperature() * 100);
2017-01-13 15:51:48 -04:00
}
2018-05-16 03:49:23 -03:00
bool GCS_MAVLINK_Sub::send_info()
2017-05-08 20:37:42 -03:00
{
// Just do this all at once, hopefully the hard-wire telemetry requirement means this is ok
// Name is char[10]
2018-05-16 03:49:23 -03:00
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("CamTilt",
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f));
2017-05-08 20:37:42 -03:00
2018-05-16 03:49:23 -03:00
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("CamPan",
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f));
2018-05-16 03:49:23 -03:00
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("TetherTrn",
sub.quarter_turn_count/4);
2017-05-08 20:37:42 -03:00
2018-05-16 03:49:23 -03:00
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("Lights1",
SRV_Channels::get_output_norm(SRV_Channel::k_rcin9) / 2.0f + 0.5f);
2017-05-08 20:37:42 -03:00
2018-05-16 03:49:23 -03:00
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("Lights2",
SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f);
2017-05-08 20:37:42 -03:00
2018-05-16 03:49:23 -03:00
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("PilotGain", sub.gain);
2017-05-08 20:37:42 -03:00
2018-05-16 03:49:23 -03:00
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("InputHold", sub.input_hold_engaged);
2017-05-08 20:37:42 -03:00
return true;
}
/*
send PID tuning message
*/
2016-01-14 15:30:56 -04:00
void Sub::send_pid_tuning(mavlink_channel_t chan)
{
const Vector3f &gyro = ahrs.get_gyro();
if (g.gcs_pid_mask & 1) {
2016-04-05 00:17:39 -03:00
const DataFlash_Class::PID_Info &pid_info = attitude_control.get_rate_roll_pid().get_pid_info();
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL,
pid_info.desired*0.01f,
degrees(gyro.x),
pid_info.FF*0.01f,
pid_info.P*0.01f,
pid_info.I*0.01f,
pid_info.D*0.01f);
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
return;
}
}
if (g.gcs_pid_mask & 2) {
2016-04-05 00:17:39 -03:00
const DataFlash_Class::PID_Info &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info();
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
pid_info.desired*0.01f,
degrees(gyro.y),
pid_info.FF*0.01f,
pid_info.P*0.01f,
pid_info.I*0.01f,
pid_info.D*0.01f);
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
return;
}
}
if (g.gcs_pid_mask & 4) {
2016-04-05 00:17:39 -03:00
const DataFlash_Class::PID_Info &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info();
mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,
pid_info.desired*0.01f,
degrees(gyro.z),
pid_info.FF*0.01f,
pid_info.P*0.01f,
pid_info.I*0.01f,
pid_info.D*0.01f);
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
return;
}
}
if (g.gcs_pid_mask & 8) {
const DataFlash_Class::PID_Info &pid_info = pos_control.get_accel_z_pid().get_pid_info();
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
pid_info.desired*0.01f,
-(ahrs.get_accel_ef_blended().z + GRAVITY_MSS),
pid_info.FF*0.01f,
pid_info.P*0.01f,
pid_info.I*0.01f,
pid_info.D*0.01f);
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
return;
}
}
}
uint8_t GCS_MAVLINK_Sub::sysid_my_gcs() const
{
return sub.g.sysid_my_gcs;
}
// try to send a message, return false if it won't fit in the serial tx buffer
bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
{
if (telemetry_delayed()) {
return false;
}
// if we don't have at least 250 micros remaining before the main loop
// wants to fire then don't send a mavlink message. We want to
// prioritise the main flight control loop over communications
2016-01-14 15:30:56 -04:00
if (sub.scheduler.time_available_usec() < 250 && sub.motors.armed()) {
gcs().set_out_of_time(true);
return false;
}
switch (id) {
2017-05-08 20:37:42 -03:00
case MSG_NAMED_FLOAT:
2018-05-16 03:49:23 -03:00
send_info();
2017-05-08 20:37:42 -03:00
break;
case MSG_EXTENDED_STATUS1:
// send extended status only once vehicle has been initialised
// to avoid unnecessary errors being reported to user
2016-01-14 15:30:56 -04:00
if (sub.ap.initialised) {
CHECK_PAYLOAD_SIZE(SYS_STATUS);
2016-01-14 15:30:56 -04:00
sub.send_extended_status1(chan);
CHECK_PAYLOAD_SIZE(POWER_STATUS);
2016-05-17 12:10:02 -03:00
send_power_status();
}
break;
case MSG_NAV_CONTROLLER_OUTPUT:
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
2016-01-14 15:30:56 -04:00
sub.send_nav_controller_output(chan);
break;
case MSG_RPM:
2016-11-25 18:58:31 -04:00
#if RPM_ENABLED == ENABLED
CHECK_PAYLOAD_SIZE(RPM);
2016-01-14 15:30:56 -04:00
sub.send_rpm(chan);
2016-11-25 18:58:31 -04:00
#endif
break;
case MSG_TERRAIN:
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
2016-01-14 15:30:56 -04:00
sub.terrain.send_request(chan);
#endif
break;
2018-05-21 05:15:54 -03:00
case MSG_FENCE_STATUS:
#if AC_FENCE == ENABLED
2018-05-21 05:15:54 -03:00
CHECK_PAYLOAD_SIZE(FENCE_STATUS);
sub.fence_send_mavlink_status(chan);
#endif
break;
case MSG_MOUNT_STATUS:
#if MOUNT == ENABLED
CHECK_PAYLOAD_SIZE(MOUNT_STATUS);
2016-01-14 15:30:56 -04:00
sub.camera_mount.status_msg(chan);
#endif // MOUNT == ENABLED
break;
case MSG_OPTICAL_FLOW:
#if OPTFLOW == ENABLED
CHECK_PAYLOAD_SIZE(OPTICAL_FLOW);
2018-01-05 23:53:55 -04:00
send_opticalflow(sub.optflow);
#endif
break;
case MSG_GIMBAL_REPORT:
#if MOUNT == ENABLED
CHECK_PAYLOAD_SIZE(GIMBAL_REPORT);
2016-01-14 15:30:56 -04:00
sub.camera_mount.send_gimbal_report(chan);
#endif
break;
case MSG_PID_TUNING:
CHECK_PAYLOAD_SIZE(PID_TUNING);
2016-01-14 15:30:56 -04:00
sub.send_pid_tuning(chan);
break;
default:
return GCS_MAVLINK::try_send_message(id);
}
return true;
}
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
// @Param: RAW_SENS
// @DisplayName: Raw sensor stream rate
// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, and SENSOR_OFFSETS to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2017-04-06 16:11:43 -03:00
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRates[STREAM_RAW_SENSORS], 0),
// @Param: EXT_STAT
// @DisplayName: Extended status stream rate to ground station
// @Description: Stream rate of SYS_STATUS, MEMINFO, MISSION_CURRENT, GPS_RAW_INT, NAV_CONTROLLER_OUTPUT, and LIMITS_STATUS to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2017-04-06 16:11:43 -03:00
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRates[STREAM_EXTENDED_STATUS], 0),
// @Param: RC_CHAN
// @DisplayName: RC Channel stream rate to ground station
// @Description: Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS_RAW to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2017-04-06 16:11:43 -03:00
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRates[STREAM_RC_CHANNELS], 0),
// @Param: POSITION
// @DisplayName: Position stream rate to ground station
// @Description: Stream rate of GLOBAL_POSITION_INT to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2017-04-06 16:11:43 -03:00
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRates[STREAM_POSITION], 0),
// @Param: EXTRA1
// @DisplayName: Extra data type 1 stream rate to ground station
// @Description: Stream rate of ATTITUDE and SIMSTATE (SITL only) to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2017-04-06 16:11:43 -03:00
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRates[STREAM_EXTRA1], 0),
// @Param: EXTRA2
// @DisplayName: Extra data type 2 stream rate to ground station
// @Description: Stream rate of VFR_HUD to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2017-04-06 16:11:43 -03:00
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRates[STREAM_EXTRA2], 0),
// @Param: EXTRA3
// @DisplayName: Extra data type 3 stream rate to ground station
// @Description: Stream rate of AHRS, HWSTATUS, and SYSTEM_TIME to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2017-04-06 16:11:43 -03:00
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRates[STREAM_EXTRA3], 0),
// @Param: PARAMS
// @DisplayName: Parameter stream rate to ground station
// @Description: Stream rate of PARAM_VALUE to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2017-04-06 16:11:43 -03:00
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[STREAM_PARAMS], 0),
AP_GROUPEND
};
static const ap_message STREAM_RAW_SENSORS_msgs[] = {
2017-08-21 03:08:52 -03:00
MSG_RAW_IMU1, // RAW_IMU, SCALED_IMU2, SCALED_IMU3
MSG_RAW_IMU2, // SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3
MSG_RAW_IMU3 // SENSOR_OFFSETS
};
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
2017-08-21 03:08:52 -03:00
MSG_EXTENDED_STATUS1, // SYS_STATUS, POWER_STATUS
MSG_EXTENDED_STATUS2, // MEMINFO
MSG_CURRENT_WAYPOINT,
MSG_GPS_RAW,
MSG_GPS_RTK,
MSG_GPS2_RAW,
MSG_GPS2_RTK,
MSG_NAV_CONTROLLER_OUTPUT,
2018-05-21 05:15:54 -03:00
MSG_FENCE_STATUS,
2017-08-21 03:08:52 -03:00
MSG_NAMED_FLOAT
};
static const ap_message STREAM_POSITION_msgs[] = {
2017-08-21 03:08:52 -03:00
MSG_LOCATION,
MSG_LOCAL_POSITION
};
static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {
2017-08-21 03:08:52 -03:00
};
static const ap_message STREAM_RC_CHANNELS_msgs[] = {
2017-08-21 03:08:52 -03:00
MSG_SERVO_OUTPUT_RAW,
MSG_RADIO_IN
};
static const ap_message STREAM_EXTRA1_msgs[] = {
2017-08-21 03:08:52 -03:00
MSG_ATTITUDE,
MSG_SIMSTATE, // SIMSTATE, AHRS2
MSG_PID_TUNING
};
static const ap_message STREAM_EXTRA2_msgs[] = {
2017-08-21 03:08:52 -03:00
MSG_VFR_HUD
};
static const ap_message STREAM_EXTRA3_msgs[] = {
2017-08-21 03:08:52 -03:00
MSG_AHRS,
MSG_HWSTATUS,
MSG_SYSTEM_TIME,
MSG_RANGEFINDER,
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
2017-08-21 03:08:52 -03:00
MSG_TERRAIN,
#endif
2017-08-21 03:08:52 -03:00
MSG_BATTERY2,
MSG_BATTERY_STATUS,
MSG_MOUNT_STATUS,
MSG_OPTICAL_FLOW,
MSG_GIMBAL_REPORT,
MSG_MAG_CAL_REPORT,
MSG_MAG_CAL_PROGRESS,
MSG_EKF_STATUS_REPORT,
MSG_VIBRATION,
2016-11-25 18:58:31 -04:00
#if RPM_ENABLED == ENABLED
MSG_RPM,
2016-11-25 18:58:31 -04:00
#endif
MSG_ESC_TELEMETRY,
2017-08-21 03:08:52 -03:00
};
2017-08-21 03:08:52 -03:00
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),
MAV_STREAM_ENTRY(STREAM_POSITION),
MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),
MAV_STREAM_ENTRY(STREAM_EXTRA1),
MAV_STREAM_ENTRY(STREAM_EXTRA2),
MAV_STREAM_ENTRY(STREAM_EXTRA3),
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
};
bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)
{
2016-05-03 01:45:37 -03:00
return sub.do_guided(cmd);
}
void GCS_MAVLINK_Sub::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
{
// add home alt if needed
if (cmd.content.location.flags.relative_alt) {
2016-01-14 15:30:56 -04:00
cmd.content.location.alt += sub.ahrs.get_home().alt;
}
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
}
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro()
{
if (sub.motors.armed()) {
gcs().send_text(MAV_SEVERITY_INFO, "Disarm before calibration.");
return MAV_RESULT_FAILED;
}
if (!sub.control_check_barometer()) {
return MAV_RESULT_FAILED;
}
AP::baro().calibrate(true);
return MAV_RESULT_ACCEPTED;
}
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
{
if (is_equal(packet.param6,1.0f)) {
// compassmot calibration
//result = sub.mavlink_compassmot(chan);
gcs().send_text(MAV_SEVERITY_INFO, "#CompassMot calibration not supported");
return MAV_RESULT_UNSUPPORTED;
}
return GCS_MAVLINK::_handle_command_preflight_calibration(packet);
}
2018-07-03 23:45:30 -03:00
MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet)
{
switch (packet.command) {
case MAV_CMD_DO_SET_HOME: {
// assume failure
if (is_equal(packet.param1, 1.0f)) {
// if param1 is 1, use current location
if (sub.set_home_to_current_location(true)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
}
// ensure param1 is zero
if (!is_zero(packet.param1)) {
return MAV_RESULT_FAILED;
}
// check frame type is supported
if (packet.frame != MAV_FRAME_GLOBAL &&
packet.frame != MAV_FRAME_GLOBAL_INT &&
packet.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT &&
packet.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
return MAV_RESULT_FAILED;
}
// sanity check location
if (!check_latlng(packet.x, packet.y)) {
return MAV_RESULT_FAILED;
}
Location new_home_loc {};
new_home_loc.lat = packet.x;
new_home_loc.lng = packet.y;
new_home_loc.alt = packet.z * 100;
// handle relative altitude
if (packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT || packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
if (!AP::ahrs().home_is_set()) {
// cannot use relative altitude if home is not set
return MAV_RESULT_FAILED;
}
new_home_loc.alt += sub.ahrs.get_home().alt;
}
if (sub.set_home(new_home_loc, true)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
}
case MAV_CMD_DO_SET_ROI: {
// param1 : /* Region of interest mode (not used)*/
// param2 : /* MISSION index/ target ID (not used)*/
// param3 : /* ROI index (not used)*/
// param4 : /* empty */
// x : lat
// y : lon
// z : alt
// sanity check location
if (!check_latlng(packet.x, packet.y)) {
return MAV_RESULT_FAILED;
}
Location roi_loc;
roi_loc.lat = packet.x;
roi_loc.lng = packet.y;
roi_loc.alt = (int32_t)(packet.z * 100.0f);
sub.set_auto_yaw_roi(roi_loc);
return MAV_RESULT_ACCEPTED;
}
default:
return GCS_MAVLINK::handle_command_int_packet(packet);
}
}
MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet)
{
switch (packet.command) {
case MAV_CMD_NAV_LOITER_UNLIM:
if (!sub.set_mode(POSHOLD, MODE_REASON_GCS_COMMAND)) {
return MAV_RESULT_FAILED;
}
return MAV_RESULT_ACCEPTED;
case MAV_CMD_NAV_LAND:
if (!sub.set_mode(SURFACE, MODE_REASON_GCS_COMMAND)) {
return MAV_RESULT_FAILED;
}
return MAV_RESULT_ACCEPTED;
case MAV_CMD_CONDITION_YAW:
// param1 : target angle [0-360]
// param2 : speed during change [deg per second]
// param3 : direction (-1:ccw, +1:cw)
// param4 : relative offset (1) or absolute angle (0)
if ((packet.param1 >= 0.0f) &&
(packet.param1 <= 360.0f) &&
(is_zero(packet.param4) || is_equal(packet.param4,1.0f))) {
sub.set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4);
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
case MAV_CMD_DO_CHANGE_SPEED:
// param1 : unused
// param2 : new speed in m/s
// param3 : unused
// param4 : unused
if (packet.param2 > 0.0f) {
sub.wp_nav.set_speed_xy(packet.param2 * 100.0f);
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
case MAV_CMD_DO_SET_HOME:
// param1 : use current (1=use current location, 0=use specified location)
// param5 : latitude
// param6 : longitude
// param7 : altitude (absolute)
if (is_equal(packet.param1,1.0f) || (is_zero(packet.param5) && is_zero(packet.param6) && is_zero(packet.param7))) {
if (sub.set_home_to_current_location(true)) {
return MAV_RESULT_ACCEPTED;
}
} else {
// ensure param1 is zero
if (!is_zero(packet.param1)) {
return MAV_RESULT_FAILED;
}
// sanity check location
if (!check_latlng(packet.param5, packet.param6)) {
return MAV_RESULT_FAILED;
}
Location new_home_loc;
new_home_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
new_home_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
new_home_loc.alt = (int32_t)(packet.param7 * 100.0f);
if (!sub.far_from_EKF_origin(new_home_loc)) {
if (sub.set_home(new_home_loc, true)) {
return MAV_RESULT_ACCEPTED;
}
}
}
return MAV_RESULT_FAILED;
case MAV_CMD_DO_SET_ROI:
// param1 : regional of interest mode (not supported)
// param2 : mission index/ target id (not supported)
// param3 : ROI index (not supported)
// param5 : x / lat
// param6 : y / lon
// param7 : z / alt
// sanity check location
if (!check_latlng(packet.param5, packet.param6)) {
return MAV_RESULT_FAILED;
}
Location roi_loc;
roi_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
roi_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
roi_loc.alt = (int32_t)(packet.param7 * 100.0f);
sub.set_auto_yaw_roi(roi_loc);
return MAV_RESULT_ACCEPTED;
#if MOUNT == ENABLED
case MAV_CMD_DO_MOUNT_CONTROL:
sub.camera_mount.control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7);
return MAV_RESULT_ACCEPTED;
#endif
case MAV_CMD_MISSION_START:
if (sub.motors.armed() && sub.set_mode(AUTO, MODE_REASON_GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
case MAV_CMD_COMPONENT_ARM_DISARM:
if (is_equal(packet.param1,1.0f)) {
// attempt to arm and return success or failure
if (sub.init_arm_motors(AP_Arming::ArmingMethod::MAVLINK)) {
return MAV_RESULT_ACCEPTED;
}
} else if (is_zero(packet.param1)) {
// force disarming by setting param2 = 21196 is deprecated
// see COMMAND_LONG DO_FLIGHTTERMINATION
sub.init_disarm_motors();
return MAV_RESULT_ACCEPTED;
} else {
return MAV_RESULT_UNSUPPORTED;
}
return MAV_RESULT_FAILED;
#if AC_FENCE == ENABLED
case MAV_CMD_DO_FENCE_ENABLE:
switch ((uint16_t)packet.param1) {
case 0:
sub.fence.enable(false);
return MAV_RESULT_ACCEPTED;
case 1:
sub.fence.enable(true);
return MAV_RESULT_ACCEPTED;
default:
break;
}
return MAV_RESULT_FAILED;
#endif
case MAV_CMD_DO_MOTOR_TEST:
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
// param3 : throttle (range depends upon param2)
// param4 : timeout (in seconds)
if (!sub.handle_do_motor_test(packet)) {
return MAV_RESULT_FAILED;
}
return MAV_RESULT_ACCEPTED;
default:
return GCS_MAVLINK::handle_command_long_packet(packet);
}
}
void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
{
switch (msg->msgid) {
case MAVLINK_MSG_ID_HEARTBEAT: { // MAV ID: 0
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
if (msg->sysid != sub.g.sysid_my_gcs) {
break;
}
2016-01-14 15:30:56 -04:00
sub.failsafe.last_heartbeat_ms = AP_HAL::millis();
break;
}
case MAVLINK_MSG_ID_PARAM_VALUE: {
#if MOUNT == ENABLED
2016-01-26 00:18:31 -04:00
sub.camera_mount.handle_param_value(msg);
#endif
2016-01-26 00:18:31 -04:00
break;
}
case MAVLINK_MSG_ID_GIMBAL_REPORT: {
#if MOUNT == ENABLED
2016-01-14 15:30:56 -04:00
handle_gimbal_report(sub.camera_mount, msg);
#endif
break;
}
case MAVLINK_MSG_ID_MANUAL_CONTROL: { // MAV ID: 69
if (msg->sysid != sub.g.sysid_my_gcs) {
break; // Only accept control from our gcs
}
mavlink_manual_control_t packet;
mavlink_msg_manual_control_decode(msg, &packet);
2018-04-03 20:20:40 -03:00
if (packet.target != sub.g.sysid_this_mav) {
break; // only accept control aimed at us
}
sub.transform_manual_control_to_rc_override(packet.x,packet.y,packet.z,packet.r,packet.buttons);
sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
sub.failsafe.last_heartbeat_ms = AP_HAL::millis();
break;
}
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: { // MAV ID: 70
2017-04-06 16:11:43 -03:00
// allow override of RC input
if (msg->sysid != sub.g.sysid_my_gcs) {
break; // Only accept control from our gcs
}
uint32_t tnow = AP_HAL::millis();
mavlink_rc_channels_override_t packet;
mavlink_msg_rc_channels_override_decode(msg, &packet);
RC_Channels::set_override(0, packet.chan1_raw, tnow);
RC_Channels::set_override(1, packet.chan2_raw, tnow);
RC_Channels::set_override(2, packet.chan3_raw, tnow);
RC_Channels::set_override(3, packet.chan4_raw, tnow);
RC_Channels::set_override(4, packet.chan5_raw, tnow);
RC_Channels::set_override(5, packet.chan6_raw, tnow);
RC_Channels::set_override(6, packet.chan7_raw, tnow);
RC_Channels::set_override(7, packet.chan8_raw, tnow);
sub.failsafe.last_pilot_input_ms = tnow;
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
sub.failsafe.last_heartbeat_ms = tnow;
break;
}
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: { // MAV ID: 82
// decode packet
mavlink_set_attitude_target_t packet;
mavlink_msg_set_attitude_target_decode(msg, &packet);
// ensure type_mask specifies to use attitude
// the thrust can be used from the altitude hold
if (packet.type_mask & (1<<6)) {
sub.set_attitude_target_no_gps = {AP_HAL::millis(), packet};
}
// ensure type_mask specifies to use attitude and thrust
if ((packet.type_mask & ((1<<7)|(1<<6))) != 0) {
break;
}
// convert thrust to climb rate
packet.thrust = constrain_float(packet.thrust, 0.0f, 1.0f);
float climb_rate_cms = 0.0f;
if (is_equal(packet.thrust, 0.5f)) {
climb_rate_cms = 0.0f;
} else if (packet.thrust > 0.5f) {
// climb at up to WPNAV_SPEED_UP
2016-01-14 15:30:56 -04:00
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * sub.wp_nav.get_speed_up();
} else {
// descend at up to WPNAV_SPEED_DN
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * fabsf(sub.wp_nav.get_speed_down());
}
2016-01-14 15:30:56 -04:00
sub.guided_set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]), climb_rate_cms);
break;
}
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: { // MAV ID: 84
// decode packet
mavlink_set_position_target_local_ned_t packet;
mavlink_msg_set_position_target_local_ned_decode(msg, &packet);
// exit if vehicle is not in Guided mode or Auto-Guided mode
2016-01-14 15:30:56 -04:00
if ((sub.control_mode != GUIDED) && !(sub.control_mode == AUTO && sub.auto_mode == Auto_NavGuided)) {
break;
}
// check for supported coordinate frames
if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
packet.coordinate_frame != MAV_FRAME_BODY_NED &&
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {
break;
}
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
/*
* for future use:
* bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE;
* bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
* bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
*/
// prepare position
Vector3f pos_vector;
if (!pos_ignore) {
// convert to cm
pos_vector = Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f);
// rotate to body-frame if necessary
if (packet.coordinate_frame == MAV_FRAME_BODY_NED ||
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
2016-01-14 15:30:56 -04:00
sub.rotate_body_frame_to_NE(pos_vector.x, pos_vector.y);
}
// add body offset if necessary
if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||
packet.coordinate_frame == MAV_FRAME_BODY_NED ||
packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
2016-01-14 15:30:56 -04:00
pos_vector += sub.inertial_nav.get_position();
} else {
// convert from alt-above-home to alt-above-ekf-origin
2016-01-14 15:30:56 -04:00
pos_vector.z = sub.pv_alt_above_origin(pos_vector.z);
}
}
// prepare velocity
Vector3f vel_vector;
if (!vel_ignore) {
// convert to cm
vel_vector = Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f);
// rotate to body-frame if necessary
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
2016-01-14 15:30:56 -04:00
sub.rotate_body_frame_to_NE(vel_vector.x, vel_vector.y);
}
}
// send request
if (!pos_ignore && !vel_ignore && acc_ignore) {
sub.guided_set_destination_posvel(pos_vector, vel_vector);
} else if (pos_ignore && !vel_ignore && acc_ignore) {
2016-01-14 15:30:56 -04:00
sub.guided_set_velocity(vel_vector);
} else if (!pos_ignore && vel_ignore && acc_ignore) {
sub.guided_set_destination(pos_vector);
}
break;
}
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: { // MAV ID: 86
// decode packet
mavlink_set_position_target_global_int_t packet;
mavlink_msg_set_position_target_global_int_decode(msg, &packet);
// exit if vehicle is not in Guided mode or Auto-Guided mode
2016-01-14 15:30:56 -04:00
if ((sub.control_mode != GUIDED) && !(sub.control_mode == AUTO && sub.auto_mode == Auto_NavGuided)) {
break;
}
// check for supported coordinate frames
if (packet.coordinate_frame != MAV_FRAME_GLOBAL &&
packet.coordinate_frame != MAV_FRAME_GLOBAL_INT &&
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT && // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT &&
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT &&
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
break;
}
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
/*
* for future use:
* bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE;
* bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
* bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
*/
Vector3f pos_neu_cm; // position (North, East, Up coordinates) in centimeters
if (!pos_ignore) {
// sanity check location
if (!check_latlng(packet.lat_int, packet.lon_int)) {
break;
}
Location loc;
loc.lat = packet.lat_int;
loc.lng = packet.lon_int;
loc.alt = packet.alt*100;
switch (packet.coordinate_frame) {
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
loc.flags.relative_alt = true;
loc.flags.terrain_alt = false;
break;
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
loc.flags.relative_alt = true;
loc.flags.terrain_alt = true;
break;
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_INT:
default:
loc.flags.relative_alt = false;
loc.flags.terrain_alt = false;
break;
}
pos_neu_cm = sub.pv_location_to_vector(loc);
}
if (!pos_ignore && !vel_ignore && acc_ignore) {
sub.guided_set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
} else if (pos_ignore && !vel_ignore && acc_ignore) {
2016-01-14 15:30:56 -04:00
sub.guided_set_velocity(Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
} else if (!pos_ignore && vel_ignore && acc_ignore) {
sub.guided_set_destination(pos_neu_cm);
}
break;
}
case MAVLINK_MSG_ID_DISTANCE_SENSOR: {
sub.rangefinder.handle_msg(msg);
break;
}
#if AC_FENCE == ENABLED
// send or receive fence points with GCS
case MAVLINK_MSG_ID_FENCE_POINT: // MAV ID: 160
case MAVLINK_MSG_ID_FENCE_FETCH_POINT:
sub.fence.handle_msg(*this, msg);
break;
#endif // AC_FENCE == ENABLED
#if MOUNT == ENABLED
//deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
case MAVLINK_MSG_ID_MOUNT_CONFIGURE: // MAV ID: 204
2016-01-14 15:30:56 -04:00
sub.camera_mount.configure_msg(msg);
break;
//deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
case MAVLINK_MSG_ID_MOUNT_CONTROL:
2016-01-14 15:30:56 -04:00
sub.camera_mount.control_msg(msg);
break;
#endif // MOUNT == ENABLED
case MAVLINK_MSG_ID_TERRAIN_DATA:
case MAVLINK_MSG_ID_TERRAIN_CHECK:
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
2016-01-14 15:30:56 -04:00
sub.terrain.handle_data(chan, msg);
#endif
break;
case MAVLINK_MSG_ID_SET_HOME_POSITION: {
mavlink_set_home_position_t packet;
mavlink_msg_set_home_position_decode(msg, &packet);
if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) {
sub.set_home_to_current_location(true);
} else {
// sanity check location
if (!check_latlng(packet.latitude, packet.longitude)) {
break;
}
Location new_home_loc;
new_home_loc.lat = packet.latitude;
new_home_loc.lng = packet.longitude;
2016-04-18 02:13:10 -03:00
new_home_loc.alt = packet.altitude / 10;
2016-01-14 15:30:56 -04:00
if (sub.far_from_EKF_origin(new_home_loc)) {
break;
}
sub.set_home(new_home_loc, true);
}
break;
}
// This adds support for leak detectors in a separate enclosure
// connected to a mavlink enabled subsystem
case MAVLINK_MSG_ID_SYS_STATUS: {
uint32_t MAV_SENSOR_WATER = 0x20000000;
mavlink_sys_status_t packet;
mavlink_msg_sys_status_decode(msg, &packet);
if ((packet.onboard_control_sensors_enabled & MAV_SENSOR_WATER) && !(packet.onboard_control_sensors_health & MAV_SENSOR_WATER)) {
sub.leak_detector.set_detect();
}
}
break;
default:
handle_common_message(msg);
break;
} // end switch
} // end handle mavlink
/*
* a delay() callback that processes MAVLink packets. We set this as the
* callback in long running library initialisation routines to allow
* MAVLink to process packets while waiting for the initialisation to
* complete
*/
2016-01-14 15:30:56 -04:00
void Sub::mavlink_delay_cb()
{
static uint32_t last_1hz, last_50hz, last_5s;
if (!gcs().chan(0).initialised) {
return;
}
DataFlash.EnableWrites(false);
uint32_t tnow = AP_HAL::millis();
if (tnow - last_1hz > 1000) {
last_1hz = tnow;
gcs_send_heartbeat();
2017-07-07 23:02:04 -03:00
gcs().send_message(MSG_EXTENDED_STATUS1);
}
if (tnow - last_50hz > 20) {
last_50hz = tnow;
gcs_update();
gcs_data_stream_send();
gcs_send_deferred();
notify.update();
}
if (tnow - last_5s > 5000) {
last_5s = tnow;
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
}
DataFlash.EnableWrites(true);
}
/*
* send data streams in the given rate range on both links
*/
void Sub::gcs_data_stream_send()
{
gcs().data_stream_send();
}
/*
* look for incoming commands on the GCS links
*/
void Sub::gcs_update()
{
gcs().update();
}
AP_Mission *GCS_MAVLINK_Sub::get_mission()
{
return &sub.mission;
}
2017-07-12 21:48:56 -03:00
AP_Rally *GCS_MAVLINK_Sub::get_rally() const
{
#if AC_RALLY == ENABLED
return &sub.rally;
#else
return nullptr;
#endif
}
MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) {
if (packet.param1 > 0.5f) {
sub.init_disarm_motors();
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
}
bool GCS_MAVLINK_Sub::set_mode(uint8_t mode)
{
return sub.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
}
int32_t GCS_MAVLINK_Sub::global_position_int_alt() const {
if (!sub.ap.depth_sensor_present) {
return 0;
}
return GCS_MAVLINK::global_position_int_alt();
}
int32_t GCS_MAVLINK_Sub::global_position_int_relative_alt() const {
if (!sub.ap.depth_sensor_present) {
return 0;
}
return GCS_MAVLINK::global_position_int_relative_alt();
}
// dummy method to avoid linking AFS
2018-03-01 14:44:02 -04:00
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }