2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2017-02-03 00:18:27 -04:00
|
|
|
|
|
|
|
#include "GCS_Mavlink.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-07-19 18:16:46 -03:00
|
|
|
// 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)
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-06-28 08:09:40 -03:00
|
|
|
void Sub::gcs_send_heartbeat()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-07-07 23:02:04 -03:00
|
|
|
gcs().send_message(MSG_HEARTBEAT);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2018-06-28 08:09:40 -03:00
|
|
|
void Sub::gcs_send_deferred()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-07-18 22:37:58 -03:00
|
|
|
gcs().retry_deferred();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* !!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
|
|
|
|
*/
|
|
|
|
|
2018-03-22 06:38:37 -03:00
|
|
|
MAV_TYPE GCS_MAVLINK_Sub::frame_type() const
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2018-03-22 06:38:37 -03:00
|
|
|
return MAV_TYPE_SUBMARINE;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-03-22 06:38:37 -03:00
|
|
|
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;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// 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
|
2018-03-22 06:38:37 -03:00
|
|
|
switch (sub.control_mode) {
|
2015-12-30 18:57:56 -04:00
|
|
|
case AUTO:
|
|
|
|
case GUIDED:
|
|
|
|
case CIRCLE:
|
|
|
|
case POSHOLD:
|
2018-04-03 11:35:43 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
|
2015-12-30 18:57:56 -04:00
|
|
|
// 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:
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// 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;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-03-22 06:38:37 -03:00
|
|
|
if (sub.motors.armed()) {
|
2018-04-03 11:35:43 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// indicate we have set a custom mode
|
2018-04-03 11:35:43 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-04-03 11:35:43 -03:00
|
|
|
return (MAV_MODE)_base_mode;
|
2018-03-22 06:38:37 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
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;
|
|
|
|
}
|
2017-02-03 00:18:27 -04:00
|
|
|
|
2018-03-22 06:38:37 -03:00
|
|
|
return MAV_STATE_STANDBY;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
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
|
|
|
|
}
|
2017-07-19 18:16:46 -03:00
|
|
|
if (ap.depth_sensor_present) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
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 &
|
2017-02-03 17:33:27 -04:00
|
|
|
~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);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
switch (control_mode) {
|
|
|
|
case ALT_HOLD:
|
|
|
|
case AUTO:
|
|
|
|
case GUIDED:
|
|
|
|
case CIRCLE:
|
2016-08-25 00:08:30 -03:00
|
|
|
case SURFACE:
|
2015-12-30 18:57:56 -04:00
|
|
|
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:
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// 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;
|
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// 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 |
|
2017-02-03 17:33:27 -04:00
|
|
|
MAV_SYS_STATUS_SENSOR_3D_MAG |
|
|
|
|
MAV_SYS_STATUS_SENSOR_GPS |
|
|
|
|
MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
|
|
|
|
|
2017-04-15 02:03:56 -03:00
|
|
|
if (sensor_health.depth) { // check the internal barometer only
|
2017-02-03 17:33:27 -04:00
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
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()) {
|
2015-12-30 18:57:56 -04:00
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
|
|
}
|
|
|
|
#if OPTFLOW == ENABLED
|
|
|
|
if (optflow.healthy()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
|
|
|
}
|
2016-07-06 16:02:36 -03:00
|
|
|
#endif
|
2017-03-09 13:50:58 -04:00
|
|
|
|
2015-12-30 18:57:56 -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;
|
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
int16_t battery_current = -1;
|
|
|
|
int8_t battery_remaining = -1;
|
|
|
|
|
|
|
|
if (battery.has_current() && battery.healthy()) {
|
2017-02-22 16:27:24 -04:00
|
|
|
// percent remaining is not necessarily accurate at the moment
|
|
|
|
//battery_remaining = battery.capacity_remaining_pct();
|
2015-12-30 18:57:56 -04:00
|
|
|
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
|
2015-12-30 18:57:56 -04:00
|
|
|
//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
|
|
|
|
|
2017-02-03 00:18:27 -04:00
|
|
|
#if RANGEFINDER_ENABLED == ENABLED
|
2017-02-26 22:32:58 -04:00
|
|
|
if (rangefinder_state.enabled) {
|
2017-02-03 17:33:27 -04:00
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
2017-02-26 22:32:58 -04:00
|
|
|
if (rangefinder.has_data_orient(ROTATION_PITCH_270)) {
|
2017-02-03 17:33:27 -04:00
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
|
|
|
|
}
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
#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,
|
2017-07-30 02:10:31 -03:00
|
|
|
(uint16_t)(scheduler.load_average() * 1000),
|
2015-12-30 18:57:56 -04:00
|
|
|
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)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
const Vector3f &targets = attitude_control.get_att_target_euler_cd();
|
|
|
|
mavlink_msg_nav_controller_output_send(
|
|
|
|
chan,
|
2017-06-19 02:39:46 -03:00
|
|
|
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,
|
2015-12-30 18:57:56 -04:00
|
|
|
0,
|
2017-02-07 13:24:39 -04:00
|
|
|
0);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2018-01-30 22:59:06 -04:00
|
|
|
int16_t GCS_MAVLINK_Sub::vfr_hud_throttle() const
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2018-01-30 22:59:06 -04:00
|
|
|
return (int16_t)(sub.motors.get_throttle() * 100);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
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)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
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
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-01-13 15:51:48 -04:00
|
|
|
// Work around to get temperature sensor data out
|
2018-05-02 23:06:53 -03:00
|
|
|
void GCS_MAVLINK_Sub::send_scaled_pressure3()
|
2017-02-03 17:33:27 -04:00
|
|
|
{
|
2018-05-02 23:06:53 -03:00
|
|
|
if (!sub.celsius.healthy()) {
|
2017-02-03 17:33:27 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
mavlink_msg_scaled_pressure3_send(
|
|
|
|
chan,
|
|
|
|
AP_HAL::millis(),
|
|
|
|
0,
|
|
|
|
0,
|
2018-05-02 23:06:53 -03:00
|
|
|
sub.celsius.temperature() * 100);
|
2017-01-13 15:51:48 -04:00
|
|
|
}
|
2015-12-30 18:57:56 -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-02-15 15:56:35 -04:00
|
|
|
|
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;
|
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
/*
|
|
|
|
send PID tuning message
|
|
|
|
*/
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::send_pid_tuning(mavlink_channel_t chan)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
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();
|
2017-02-03 17:33:27 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL,
|
2015-12-30 18:57:56 -04:00
|
|
|
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();
|
2017-02-03 17:33:27 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
|
2015-12-30 18:57:56 -04:00
|
|
|
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();
|
2017-02-03 17:33:27 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,
|
2015-12-30 18:57:56 -04:00
|
|
|
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) {
|
2018-01-15 07:58:57 -04:00
|
|
|
const DataFlash_Class::PID_Info &pid_info = pos_control.get_accel_z_pid().get_pid_info();
|
2017-02-03 17:33:27 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
|
2015-12-30 18:57:56 -04:00
|
|
|
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;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-07-12 04:51:23 -03:00
|
|
|
uint8_t GCS_MAVLINK_Sub::sysid_my_gcs() const
|
|
|
|
{
|
|
|
|
return sub.g.sysid_my_gcs;
|
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// try to send a message, return false if it won't fit in the serial tx buffer
|
2017-02-03 00:18:27 -04:00
|
|
|
bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-07-12 05:11:24 -03:00
|
|
|
if (telemetry_delayed()) {
|
2015-12-30 18:57:56 -04:00
|
|
|
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()) {
|
2017-08-20 23:32:48 -03:00
|
|
|
gcs().set_out_of_time(true);
|
2015-12-30 18:57:56 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
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;
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
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) {
|
2015-12-30 18:57:56 -04:00
|
|
|
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
2016-01-14 15:30:56 -04:00
|
|
|
sub.send_extended_status1(chan);
|
2015-12-30 18:57:56 -04:00
|
|
|
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
2016-05-17 12:10:02 -03:00
|
|
|
send_power_status();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
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);
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_RPM:
|
2016-11-25 18:58:31 -04:00
|
|
|
#if RPM_ENABLED == ENABLED
|
2015-12-30 18:57:56 -04:00
|
|
|
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
|
2015-12-30 18:57:56 -04:00
|
|
|
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);
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
|
2018-05-21 05:15:54 -03:00
|
|
|
case MSG_FENCE_STATUS:
|
2015-12-30 18:57:56 -04:00
|
|
|
#if AC_FENCE == ENABLED
|
2018-05-21 05:15:54 -03:00
|
|
|
CHECK_PAYLOAD_SIZE(FENCE_STATUS);
|
|
|
|
sub.fence_send_mavlink_status(chan);
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_MOUNT_STATUS:
|
|
|
|
#if MOUNT == ENABLED
|
2017-02-03 17:33:27 -04:00
|
|
|
CHECK_PAYLOAD_SIZE(MOUNT_STATUS);
|
2016-01-14 15:30:56 -04:00
|
|
|
sub.camera_mount.status_msg(chan);
|
2015-12-30 18:57:56 -04:00
|
|
|
#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);
|
2015-12-30 18:57:56 -04:00
|
|
|
#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);
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_PID_TUNING:
|
|
|
|
CHECK_PAYLOAD_SIZE(PID_TUNING);
|
2016-01-14 15:30:56 -04:00
|
|
|
sub.send_pid_tuning(chan);
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
|
2017-07-17 22:21:35 -03:00
|
|
|
default:
|
|
|
|
return GCS_MAVLINK::try_send_message(id);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
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),
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// @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),
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// @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),
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// @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),
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// @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),
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// @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),
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// @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),
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// @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),
|
2017-02-03 17:33:27 -04:00
|
|
|
AP_GROUPEND
|
2015-12-30 18:57:56 -04:00
|
|
|
};
|
|
|
|
|
2018-05-21 01:07:03 -03:00
|
|
|
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
|
|
|
|
};
|
2018-05-21 01:07:03 -03:00
|
|
|
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
|
|
|
|
};
|
2018-05-21 01:07:03 -03:00
|
|
|
static const ap_message STREAM_POSITION_msgs[] = {
|
2017-08-21 03:08:52 -03:00
|
|
|
MSG_LOCATION,
|
|
|
|
MSG_LOCAL_POSITION
|
|
|
|
};
|
2018-05-21 01:07:03 -03:00
|
|
|
static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {
|
2017-08-21 03:08:52 -03:00
|
|
|
};
|
2018-05-21 01:07:03 -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
|
|
|
|
};
|
2018-05-21 01:07:03 -03:00
|
|
|
static const ap_message STREAM_EXTRA1_msgs[] = {
|
2017-08-21 03:08:52 -03:00
|
|
|
MSG_ATTITUDE,
|
|
|
|
MSG_SIMSTATE, // SIMSTATE, AHRS2
|
|
|
|
MSG_PID_TUNING
|
|
|
|
};
|
2018-05-21 01:07:03 -03:00
|
|
|
static const ap_message STREAM_EXTRA2_msgs[] = {
|
2017-08-21 03:08:52 -03:00
|
|
|
MSG_VFR_HUD
|
|
|
|
};
|
2018-05-21 01:07:03 -03:00
|
|
|
static const ap_message STREAM_EXTRA3_msgs[] = {
|
2017-08-21 03:08:52 -03:00
|
|
|
MSG_AHRS,
|
|
|
|
MSG_HWSTATUS,
|
|
|
|
MSG_SYSTEM_TIME,
|
|
|
|
MSG_RANGEFINDER,
|
2015-12-30 18:57:56 -04:00
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
2017-08-21 03:08:52 -03:00
|
|
|
MSG_TERRAIN,
|
2015-12-30 18:57:56 -04:00
|
|
|
#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
|
2018-06-20 20:51:06 -03:00
|
|
|
MSG_RPM,
|
2016-11-25 18:58:31 -04:00
|
|
|
#endif
|
2018-06-20 20:51:06 -03:00
|
|
|
MSG_ESC_TELEMETRY,
|
2017-08-21 03:08:52 -03:00
|
|
|
};
|
2015-12-30 18:57:56 -04: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
|
|
|
|
};
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 00:18:27 -04:00
|
|
|
bool GCS_MAVLINK_Sub::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2016-05-03 01:45:37 -03:00
|
|
|
return sub.do_guided(cmd);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-02-03 00:18:27 -04:00
|
|
|
void GCS_MAVLINK_Sub::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// 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;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
|
|
|
|
}
|
|
|
|
|
2018-03-18 01:18:59 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro()
|
2018-03-17 08:35:01 -03:00
|
|
|
{
|
2018-04-22 12:37:03 -03:00
|
|
|
if (sub.motors.armed()) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Disarm before calibration.");
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
|
2018-04-22 12:27:22 -03:00
|
|
|
if (!sub.control_check_barometer()) {
|
2018-03-18 01:18:59 -03:00
|
|
|
return MAV_RESULT_FAILED;
|
2018-03-17 08:35:01 -03:00
|
|
|
}
|
|
|
|
|
2018-03-18 01:18:59 -03:00
|
|
|
AP::baro().calibrate(true);
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
|
|
|
|
MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
|
|
|
{
|
2018-03-17 08:35:01 -03:00
|
|
|
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);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2018-07-03 23:53:57 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2018-07-03 23:53:57 -03:00
|
|
|
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;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-07-03 23:53:57 -03:00
|
|
|
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)
|
|
|
|
{
|
2015-12-30 18:57:56 -04:00
|
|
|
switch (msg->msgid) {
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT: { // MAV ID: 0
|
2015-12-30 18:57:56 -04:00
|
|
|
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
2017-02-03 17:33:27 -04:00
|
|
|
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();
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_PARAM_VALUE: {
|
2018-04-20 09:41:04 -03:00
|
|
|
#if MOUNT == ENABLED
|
2016-01-26 00:18:31 -04:00
|
|
|
sub.camera_mount.handle_param_value(msg);
|
2018-04-20 09:41:04 -03:00
|
|
|
#endif
|
2016-01-26 00:18:31 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_GIMBAL_REPORT: {
|
2015-12-30 18:57:56 -04:00
|
|
|
#if MOUNT == ENABLED
|
2016-01-14 15:30:56 -04:00
|
|
|
handle_gimbal_report(sub.camera_mount, msg);
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
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);
|
2016-01-10 20:23:03 -04:00
|
|
|
|
2018-04-03 20:20:40 -03:00
|
|
|
if (packet.target != sub.g.sysid_this_mav) {
|
|
|
|
break; // only accept control aimed at us
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
sub.transform_manual_control_to_rc_override(packet.x,packet.y,packet.z,packet.r,packet.buttons);
|
2016-01-10 20:23:03 -04:00
|
|
|
|
2017-04-14 16:58:54 -03:00
|
|
|
sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
|
2017-02-03 17:33:27 -04:00
|
|
|
// 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;
|
|
|
|
}
|
2016-01-10 15:32:45 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: { // MAV ID: 70
|
2017-04-06 16:11:43 -03:00
|
|
|
// allow override of RC input
|
2017-02-03 17:33:27 -04:00
|
|
|
if (msg->sysid != sub.g.sysid_my_gcs) {
|
|
|
|
break; // Only accept control from our gcs
|
|
|
|
}
|
2018-05-29 03:26:16 -03:00
|
|
|
|
|
|
|
uint32_t tnow = AP_HAL::millis();
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
mavlink_rc_channels_override_t packet;
|
|
|
|
mavlink_msg_rc_channels_override_decode(msg, &packet);
|
|
|
|
|
2018-05-29 03:26:16 -03:00
|
|
|
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);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-05-29 03:26:16 -03:00
|
|
|
sub.failsafe.last_pilot_input_ms = tnow;
|
2015-12-30 18:57:56 -04:00
|
|
|
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
|
2018-05-29 03:26:16 -03:00
|
|
|
sub.failsafe.last_heartbeat_ms = tnow;
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: { // MAV ID: 82
|
2015-12-30 18:57:56 -04:00
|
|
|
// decode packet
|
|
|
|
mavlink_set_attitude_target_t packet;
|
|
|
|
mavlink_msg_set_attitude_target_decode(msg, &packet);
|
|
|
|
|
2018-04-14 00:15:15 -03:00
|
|
|
// 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};
|
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// 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();
|
2015-12-30 18:57:56 -04:00
|
|
|
} else {
|
|
|
|
// descend at up to WPNAV_SPEED_DN
|
2018-04-13 18:34:59 -03:00
|
|
|
climb_rate_cms = (packet.thrust - 0.5f) * 2.0f * fabsf(sub.wp_nav.get_speed_down());
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
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);
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: { // MAV ID: 84
|
2015-12-30 18:57:56 -04:00
|
|
|
// 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)) {
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for supported coordinate frames
|
|
|
|
if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
|
2017-02-03 17:33:27 -04:00
|
|
|
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_BODY_NED &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {
|
2015-12-30 18:57:56 -04:00
|
|
|
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 ||
|
2017-02-03 17:33:27 -04:00
|
|
|
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);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
// add body offset if necessary
|
|
|
|
if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED ||
|
2017-02-03 17:33:27 -04:00
|
|
|
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();
|
2015-12-30 18:57:56 -04:00
|
|
|
} 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);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// send request
|
|
|
|
if (!pos_ignore && !vel_ignore && acc_ignore) {
|
2018-07-03 23:53:57 -03:00
|
|
|
sub.guided_set_destination_posvel(pos_vector, vel_vector);
|
2015-12-30 18:57:56 -04:00
|
|
|
} else if (pos_ignore && !vel_ignore && acc_ignore) {
|
2016-01-14 15:30:56 -04:00
|
|
|
sub.guided_set_velocity(vel_vector);
|
2015-12-30 18:57:56 -04:00
|
|
|
} else if (!pos_ignore && vel_ignore && acc_ignore) {
|
2018-07-03 23:53:57 -03:00
|
|
|
sub.guided_set_destination(pos_vector);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: { // MAV ID: 86
|
2015-12-30 18:57:56 -04:00
|
|
|
// 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)) {
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for supported coordinate frames
|
2017-09-18 23:57:40 -03:00
|
|
|
if (packet.coordinate_frame != MAV_FRAME_GLOBAL &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_INT &&
|
2017-02-03 17:33:27 -04:00
|
|
|
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 &&
|
2017-09-18 23:57:40 -03:00
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT &&
|
2017-02-03 17:33:27 -04:00
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
|
|
|
|
break;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
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;
|
|
|
|
*/
|
|
|
|
|
2017-12-03 13:12:38 -04:00
|
|
|
Vector3f pos_neu_cm; // position (North, East, Up coordinates) in centimeters
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
if (!pos_ignore) {
|
|
|
|
// sanity check location
|
2017-02-03 00:18:27 -04:00
|
|
|
if (!check_latlng(packet.lat_int, packet.lon_int)) {
|
|
|
|
break;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
Location loc;
|
|
|
|
loc.lat = packet.lat_int;
|
|
|
|
loc.lng = packet.lon_int;
|
|
|
|
loc.alt = packet.alt*100;
|
|
|
|
switch (packet.coordinate_frame) {
|
2017-02-03 17:33:27 -04:00
|
|
|
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;
|
2017-09-18 23:57:40 -03:00
|
|
|
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
|
|
|
|
loc.flags.relative_alt = true;
|
|
|
|
loc.flags.terrain_alt = true;
|
|
|
|
break;
|
2017-09-18 23:57:40 -03:00
|
|
|
case MAV_FRAME_GLOBAL:
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAV_FRAME_GLOBAL_INT:
|
|
|
|
default:
|
|
|
|
loc.flags.relative_alt = false;
|
|
|
|
loc.flags.terrain_alt = false;
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
2017-12-03 13:12:38 -04:00
|
|
|
pos_neu_cm = sub.pv_location_to_vector(loc);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
if (!pos_ignore && !vel_ignore && acc_ignore) {
|
2018-07-03 23:53:57 -03:00
|
|
|
sub.guided_set_destination_posvel(pos_neu_cm, Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f));
|
2015-12-30 18:57:56 -04:00
|
|
|
} 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));
|
2015-12-30 18:57:56 -04:00
|
|
|
} else if (!pos_ignore && vel_ignore && acc_ignore) {
|
2018-07-03 23:53:57 -03:00
|
|
|
sub.guided_set_destination(pos_neu_cm);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_DISTANCE_SENSOR: {
|
2017-02-03 00:18:27 -04:00
|
|
|
sub.rangefinder.handle_msg(msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-07-05 21:18:58 -03:00
|
|
|
#if AC_FENCE == ENABLED
|
2017-02-03 17:33:27 -04:00
|
|
|
// send or receive fence points with GCS
|
2016-07-05 21:18:58 -03:00
|
|
|
case MAVLINK_MSG_ID_FENCE_POINT: // MAV ID: 160
|
|
|
|
case MAVLINK_MSG_ID_FENCE_FETCH_POINT:
|
2017-07-09 05:32:02 -03:00
|
|
|
sub.fence.handle_msg(*this, msg);
|
2016-07-05 21:18:58 -03:00
|
|
|
break;
|
|
|
|
#endif // AC_FENCE == ENABLED
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
#if MOUNT == ENABLED
|
2017-02-03 17:33:27 -04:00
|
|
|
//deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAVLINK_MSG_ID_MOUNT_CONFIGURE: // MAV ID: 204
|
2016-01-14 15:30:56 -04:00
|
|
|
sub.camera_mount.configure_msg(msg);
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
2017-02-03 17:33:27 -04:00
|
|
|
//deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
2016-01-14 15:30:56 -04:00
|
|
|
sub.camera_mount.control_msg(msg);
|
2015-12-30 18:57:56 -04:00
|
|
|
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);
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAVLINK_MSG_ID_SET_HOME_POSITION: {
|
2015-12-30 18:57:56 -04:00
|
|
|
mavlink_set_home_position_t packet;
|
|
|
|
mavlink_msg_set_home_position_decode(msg, &packet);
|
2017-02-03 17:33:27 -04:00
|
|
|
if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) {
|
2017-06-05 05:04:04 -03:00
|
|
|
sub.set_home_to_current_location(true);
|
2015-12-30 18:57:56 -04:00
|
|
|
} else {
|
|
|
|
// sanity check location
|
2017-02-03 17:33:27 -04:00
|
|
|
if (!check_latlng(packet.latitude, packet.longitude)) {
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
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)) {
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
}
|
2017-06-05 05:04:04 -03:00
|
|
|
sub.set_home(new_home_loc, true);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-04-16 15:11:15 -03:00
|
|
|
// This adds support for leak detectors in a separate enclosure
|
|
|
|
// connected to a mavlink enabled subsystem
|
2017-03-01 23:25:41 -04:00
|
|
|
case MAVLINK_MSG_ID_SYS_STATUS: {
|
2017-02-03 17:33:27 -04:00
|
|
|
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();
|
|
|
|
}
|
2017-03-01 23:25:41 -04:00
|
|
|
}
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2017-02-03 00:18:27 -04:00
|
|
|
|
2017-03-01 23:25:41 -04:00
|
|
|
default:
|
|
|
|
handle_common_message(msg);
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
} // 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()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
static uint32_t last_1hz, last_50hz, last_5s;
|
2018-05-08 03:33:49 -03:00
|
|
|
if (!gcs().chan(0).initialised) {
|
2017-02-03 17:33:27 -04:00
|
|
|
return;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-06-14 23:09:08 -03:00
|
|
|
DataFlash.EnableWrites(false);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-04-13 20:05:16 -03:00
|
|
|
uint32_t tnow = AP_HAL::millis();
|
2015-12-30 18:57:56 -04:00
|
|
|
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);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
if (tnow - last_50hz > 20) {
|
|
|
|
last_50hz = tnow;
|
2018-08-23 02:18:03 -03:00
|
|
|
gcs_update();
|
2015-12-30 18:57:56 -04:00
|
|
|
gcs_data_stream_send();
|
|
|
|
gcs_send_deferred();
|
|
|
|
notify.update();
|
|
|
|
}
|
|
|
|
if (tnow - last_5s > 5000) {
|
|
|
|
last_5s = tnow;
|
2017-07-08 22:51:41 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-06-14 23:09:08 -03:00
|
|
|
DataFlash.EnableWrites(true);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* send data streams in the given rate range on both links
|
|
|
|
*/
|
2018-06-28 08:09:40 -03:00
|
|
|
void Sub::gcs_data_stream_send()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-21 20:54:56 -04:00
|
|
|
gcs().data_stream_send();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* look for incoming commands on the GCS links
|
|
|
|
*/
|
2018-08-23 02:18:03 -03:00
|
|
|
void Sub::gcs_update()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-21 20:54:56 -04:00
|
|
|
gcs().update();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
2017-07-08 00:23:40 -03:00
|
|
|
|
|
|
|
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
|
|
|
|
}
|
2017-07-27 02:23:40 -03:00
|
|
|
|
|
|
|
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;
|
|
|
|
}
|
|
|
|
|
2017-08-11 03:18:45 -03:00
|
|
|
bool GCS_MAVLINK_Sub::set_mode(uint8_t mode)
|
|
|
|
{
|
|
|
|
return sub.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
|
|
|
|
}
|
|
|
|
|
2018-05-01 09:05:41 -03:00
|
|
|
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();
|
|
|
|
}
|
|
|
|
|
2017-07-27 02:23:40 -03:00
|
|
|
// 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; }
|