2016-05-27 10:14:08 -03:00
|
|
|
#include "GCS_Mavlink.h"
|
2015-06-01 02:04:25 -03:00
|
|
|
#include "Tracker.h"
|
|
|
|
|
2019-03-01 20:08:01 -04:00
|
|
|
MAV_TYPE GCS_Tracker::frame_type() const
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2018-03-22 06:30:44 -03:00
|
|
|
return MAV_TYPE_ANTENNA_TRACKER;
|
|
|
|
}
|
2014-03-06 18:13:53 -04:00
|
|
|
|
2018-03-22 06:30:44 -03:00
|
|
|
MAV_MODE GCS_MAVLINK_Tracker::base_mode() const
|
|
|
|
{
|
2018-04-03 11:34:55 -03:00
|
|
|
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
2014-03-06 18:13:53 -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
|
2019-09-13 12:41:55 -03:00
|
|
|
switch (tracker.mode->number()) {
|
|
|
|
case Mode::Number::MANUAL:
|
2018-04-03 11:34:55 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
2014-03-06 18:13:53 -04:00
|
|
|
break;
|
|
|
|
|
2019-09-13 12:41:55 -03:00
|
|
|
case Mode::Number::STOP:
|
2014-03-22 05:08:17 -03:00
|
|
|
break;
|
|
|
|
|
2019-09-13 12:41:55 -03:00
|
|
|
case Mode::Number::SCAN:
|
|
|
|
case Mode::Number::SERVOTEST:
|
|
|
|
case Mode::Number::AUTO:
|
2019-09-25 06:55:59 -03:00
|
|
|
case Mode::Number::GUIDED:
|
2018-04-03 11:34:55 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED |
|
2014-03-12 00:36:51 -03:00
|
|
|
MAV_MODE_FLAG_STABILIZE_ENABLED;
|
2014-03-06 18:13:53 -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;
|
|
|
|
|
2019-09-13 12:41:55 -03:00
|
|
|
case Mode::Number::INITIALISING:
|
2014-03-06 18:13:53 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-07-05 23:09:09 -03:00
|
|
|
// we are armed if safety switch is not disarmed
|
2019-02-28 17:38:28 -04:00
|
|
|
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED &&
|
2019-09-13 12:41:55 -03:00
|
|
|
tracker.mode != &tracker.mode_initialising &&
|
2019-02-28 17:38:28 -04:00
|
|
|
hal.util->get_soft_armed()) {
|
2018-04-03 11:34:55 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
2016-07-05 23:09:09 -03:00
|
|
|
}
|
|
|
|
|
2018-04-03 11:34:55 -03:00
|
|
|
return (MAV_MODE)_base_mode;
|
2018-03-22 06:30:44 -03:00
|
|
|
}
|
|
|
|
|
2019-03-01 20:08:01 -04:00
|
|
|
uint32_t GCS_Tracker::custom_mode() const
|
2018-03-22 06:30:44 -03:00
|
|
|
{
|
2019-09-13 12:41:55 -03:00
|
|
|
return (uint32_t)tracker.mode->number();
|
2018-03-22 06:30:44 -03:00
|
|
|
}
|
|
|
|
|
2019-11-25 22:46:14 -04:00
|
|
|
MAV_STATE GCS_MAVLINK_Tracker::vehicle_system_status() const
|
2018-03-22 06:30:44 -03:00
|
|
|
{
|
2019-09-13 12:41:55 -03:00
|
|
|
if (tracker.mode == &tracker.mode_initialising) {
|
2018-03-22 06:30:44 -03:00
|
|
|
return MAV_STATE_CALIBRATING;
|
|
|
|
}
|
|
|
|
return MAV_STATE_ACTIVE;
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
2019-02-17 20:24:23 -04:00
|
|
|
void GCS_MAVLINK_Tracker::send_nav_controller_output() const
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2019-02-17 20:24:23 -04:00
|
|
|
float alt_diff = (tracker.g.alt_source == ALT_SOURCE_BARO) ? tracker.nav_status.alt_difference_baro : tracker.nav_status.alt_difference_gps;
|
2016-05-24 08:53:57 -03:00
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
mavlink_msg_nav_controller_output_send(
|
|
|
|
chan,
|
|
|
|
0,
|
2019-02-17 20:24:23 -04:00
|
|
|
tracker.nav_status.pitch,
|
|
|
|
tracker.nav_status.bearing,
|
|
|
|
tracker.nav_status.bearing,
|
|
|
|
MIN(tracker.nav_status.distance, UINT16_MAX),
|
2016-05-24 08:53:57 -03:00
|
|
|
alt_diff,
|
2013-10-13 04:14:13 -03:00
|
|
|
0,
|
|
|
|
0);
|
|
|
|
}
|
|
|
|
|
2019-09-25 06:55:59 -03:00
|
|
|
void GCS_MAVLINK_Tracker::handle_set_attitude_target(const mavlink_message_t &msg)
|
|
|
|
{
|
|
|
|
// decode packet
|
|
|
|
mavlink_set_attitude_target_t packet;
|
|
|
|
mavlink_msg_set_attitude_target_decode(&msg, &packet);
|
|
|
|
|
|
|
|
// exit if vehicle is not in Guided mode
|
|
|
|
if (tracker.mode != &tracker.mode_guided) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// sanity checks:
|
|
|
|
if (!is_zero(packet.body_roll_rate)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (!(packet.type_mask & (1<<0))) {
|
|
|
|
// not told to ignore body roll rate
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (!(packet.type_mask & (1<<6))) {
|
|
|
|
// not told to ignore throttle
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (packet.type_mask & (1<<7)) {
|
|
|
|
// told to ignore attitude (we don't allow continuous motion yet)
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if ((packet.type_mask & (1<<3)) && (packet.type_mask&(1<<4))) {
|
|
|
|
// told to ignore both pitch and yaw rates - nothing to do?!
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
const bool use_yaw_rate = !(packet.type_mask & (1<<2));
|
|
|
|
|
|
|
|
tracker.mode_guided.set_angle(
|
|
|
|
Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]),
|
|
|
|
use_yaw_rate,
|
|
|
|
packet.body_yaw_rate);
|
|
|
|
}
|
|
|
|
|
2019-02-28 17:38:28 -04:00
|
|
|
/*
|
|
|
|
send PID tuning message
|
|
|
|
*/
|
2019-02-28 19:32:16 -04:00
|
|
|
void GCS_MAVLINK_Tracker::send_pid_tuning()
|
2019-02-28 17:38:28 -04:00
|
|
|
{
|
2019-02-28 19:32:16 -04:00
|
|
|
const Parameters &g = tracker.g;
|
2019-02-28 17:38:28 -04:00
|
|
|
|
|
|
|
// Pitch PID
|
|
|
|
if (g.gcs_pid_mask & 1) {
|
2022-03-03 23:29:49 -04:00
|
|
|
const AP_PIDInfo *pid_info = &g.pidPitch2Srv.get_pid_info();
|
2019-02-28 17:38:28 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
|
2019-06-27 06:31:52 -03:00
|
|
|
pid_info->target,
|
2019-02-28 17:38:28 -04:00
|
|
|
pid_info->actual,
|
|
|
|
pid_info->FF,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
2021-08-14 00:11:09 -03:00
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
2019-02-28 17:38:28 -04:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// Yaw PID
|
|
|
|
if (g.gcs_pid_mask & 2) {
|
2022-03-03 23:29:49 -04:00
|
|
|
const AP_PIDInfo *pid_info = &g.pidYaw2Srv.get_pid_info();
|
2019-02-28 17:38:28 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW,
|
2019-06-27 06:31:52 -03:00
|
|
|
pid_info->target,
|
2019-02-28 17:38:28 -04:00
|
|
|
pid_info->actual,
|
|
|
|
pid_info->FF,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
2021-08-14 00:11:09 -03:00
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
2019-02-28 17:38:28 -04:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2016-05-27 10:14:08 -03:00
|
|
|
bool GCS_MAVLINK_Tracker::handle_guided_request(AP_Mission::Mission_Command&)
|
2015-08-15 07:43:48 -03:00
|
|
|
{
|
|
|
|
// do nothing
|
2016-04-26 07:15:47 -03:00
|
|
|
return false;
|
2015-08-15 07:43:48 -03:00
|
|
|
}
|
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
/*
|
|
|
|
default stream rates to 1Hz
|
|
|
|
*/
|
2019-06-19 08:13:57 -03:00
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Param: RAW_SENS
|
|
|
|
// @DisplayName: Raw sensor stream rate
|
|
|
|
// @Description: Raw sensor stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1),
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// @Param: EXT_STAT
|
|
|
|
// @DisplayName: Extended status stream rate to ground station
|
|
|
|
// @Description: Extended status stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1),
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// @Param: RC_CHAN
|
|
|
|
// @DisplayName: RC Channel stream rate to ground station
|
|
|
|
// @Description: RC Channel stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1),
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// @Param: RAW_CTRL
|
|
|
|
// @DisplayName: Raw Control stream rate to ground station
|
|
|
|
// @Description: Raw Control stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1),
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// @Param: POSITION
|
|
|
|
// @DisplayName: Position stream rate to ground station
|
|
|
|
// @Description: Position stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1),
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// @Param: EXTRA1
|
|
|
|
// @DisplayName: Extra data type 1 stream rate to ground station
|
|
|
|
// @Description: Extra data type 1 stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1),
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// @Param: EXTRA2
|
|
|
|
// @DisplayName: Extra data type 2 stream rate to ground station
|
|
|
|
// @Description: Extra data type 2 stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1),
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// @Param: EXTRA3
|
|
|
|
// @DisplayName: Extra data type 3 stream rate to ground station
|
|
|
|
// @Description: Extra data type 3 stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1),
|
2013-10-13 04:14:13 -03:00
|
|
|
|
|
|
|
// @Param: PARAMS
|
|
|
|
// @DisplayName: Parameter stream rate to ground station
|
|
|
|
// @Description: Parameter stream rate to ground station
|
|
|
|
// @Units: Hz
|
2021-02-19 11:32:28 -04:00
|
|
|
// @Range: 0 50
|
2013-10-13 04:14:13 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:10 -04:00
|
|
|
// @RebootRequired: True
|
2013-10-13 04:14:13 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:13:57 -03:00
|
|
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),
|
2013-10-13 04:14:13 -03:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
2018-05-21 01:07:13 -03:00
|
|
|
static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
2018-12-04 20:36:57 -04:00
|
|
|
MSG_RAW_IMU,
|
|
|
|
MSG_SCALED_IMU2,
|
|
|
|
MSG_SCALED_IMU3,
|
2018-12-07 02:29:22 -04:00
|
|
|
MSG_SCALED_PRESSURE,
|
|
|
|
MSG_SCALED_PRESSURE2,
|
|
|
|
MSG_SCALED_PRESSURE3,
|
2017-08-21 03:09:04 -03:00
|
|
|
};
|
2018-05-21 01:07:13 -03:00
|
|
|
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
2018-12-17 22:07:36 -04:00
|
|
|
MSG_SYS_STATUS,
|
|
|
|
MSG_POWER_STATUS,
|
2021-08-23 01:56:22 -03:00
|
|
|
MSG_MCU_STATUS,
|
2018-12-04 01:18:26 -04:00
|
|
|
MSG_MEMINFO,
|
2017-08-21 03:09:04 -03:00
|
|
|
MSG_NAV_CONTROLLER_OUTPUT,
|
|
|
|
MSG_GPS_RAW,
|
|
|
|
MSG_GPS_RTK,
|
|
|
|
MSG_GPS2_RAW,
|
|
|
|
MSG_GPS2_RTK,
|
|
|
|
};
|
2018-05-21 01:07:13 -03:00
|
|
|
static const ap_message STREAM_POSITION_msgs[] = {
|
2017-08-21 03:09:04 -03:00
|
|
|
MSG_LOCATION,
|
|
|
|
MSG_LOCAL_POSITION
|
|
|
|
};
|
2018-05-21 01:07:13 -03:00
|
|
|
static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {
|
2017-08-21 03:09:04 -03:00
|
|
|
MSG_SERVO_OUTPUT_RAW,
|
|
|
|
};
|
2018-05-21 01:07:13 -03:00
|
|
|
static const ap_message STREAM_RC_CHANNELS_msgs[] = {
|
2019-07-06 20:02:06 -03:00
|
|
|
MSG_RC_CHANNELS,
|
|
|
|
MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection
|
2017-08-21 03:09:04 -03:00
|
|
|
};
|
2018-05-21 01:07:13 -03:00
|
|
|
static const ap_message STREAM_EXTRA1_msgs[] = {
|
2017-08-21 03:09:04 -03:00
|
|
|
MSG_ATTITUDE,
|
2019-02-28 17:38:28 -04:00
|
|
|
MSG_PID_TUNING,
|
2017-08-21 03:09:04 -03:00
|
|
|
};
|
2018-05-21 01:07:13 -03:00
|
|
|
static const ap_message STREAM_EXTRA3_msgs[] = {
|
2017-08-21 03:09:04 -03:00
|
|
|
MSG_AHRS,
|
2018-12-18 16:23:06 -04:00
|
|
|
MSG_SIMSTATE,
|
2019-08-06 04:09:08 -03:00
|
|
|
MSG_SYSTEM_TIME,
|
2018-12-18 16:23:06 -04:00
|
|
|
MSG_AHRS2,
|
2017-08-21 03:09:04 -03:00
|
|
|
MSG_MAG_CAL_REPORT,
|
|
|
|
MSG_MAG_CAL_PROGRESS,
|
2019-03-26 03:18:42 -03:00
|
|
|
MSG_EKF_STATUS_REPORT,
|
2017-08-21 03:09:04 -03:00
|
|
|
};
|
2018-05-22 22:23:28 -03:00
|
|
|
static const ap_message STREAM_PARAMS_msgs[] = {
|
|
|
|
MSG_NEXT_PARAM
|
|
|
|
};
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2017-08-21 03:09:04 -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_RAW_CONTROLLER),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_EXTRA1),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_EXTRA3),
|
2018-05-22 22:23:28 -03:00
|
|
|
MAV_STREAM_ENTRY(STREAM_PARAMS),
|
2017-08-21 03:09:04 -03:00
|
|
|
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
|
|
|
|
};
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2014-12-09 23:32:30 -04:00
|
|
|
/*
|
|
|
|
We eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and
|
|
|
|
MAVLINK_MSG_ID_SCALED_PRESSUREs
|
|
|
|
*/
|
2018-03-17 03:38:43 -03:00
|
|
|
void GCS_MAVLINK_Tracker::packetReceived(const mavlink_status_t &status,
|
2019-04-30 07:22:50 -03:00
|
|
|
const mavlink_message_t &msg)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2015-04-27 04:44:32 -03:00
|
|
|
// return immediately if sysid doesn't match our target sysid
|
2018-03-17 03:38:43 -03:00
|
|
|
if ((tracker.g.sysid_target != 0) && (tracker.g.sysid_target != msg.sysid)) {
|
2019-02-08 18:37:33 -04:00
|
|
|
GCS_MAVLINK::packetReceived(status, msg);
|
2015-04-27 04:44:32 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2018-03-17 03:38:43 -03:00
|
|
|
switch (msg.msgid) {
|
2015-04-27 04:44:32 -03:00
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT:
|
|
|
|
{
|
|
|
|
mavlink_check_target(msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2014-12-09 23:32:30 -04:00
|
|
|
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_global_position_int_t packet;
|
2018-03-17 03:38:43 -03:00
|
|
|
mavlink_msg_global_position_int_decode(&msg, &packet);
|
|
|
|
tracker.tracking_update_position(packet);
|
2014-12-09 23:32:30 -04:00
|
|
|
break;
|
2014-05-13 23:11:22 -03:00
|
|
|
}
|
2014-12-09 23:32:30 -04:00
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_SCALED_PRESSURE:
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_scaled_pressure_t packet;
|
2018-03-17 03:38:43 -03:00
|
|
|
mavlink_msg_scaled_pressure_decode(&msg, &packet);
|
|
|
|
tracker.tracking_update_pressure(packet);
|
2014-12-09 23:32:30 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2018-03-17 03:38:43 -03:00
|
|
|
GCS_MAVLINK::packetReceived(status, msg);
|
2014-12-09 23:32:30 -04:00
|
|
|
}
|
2014-05-13 23:11:22 -03:00
|
|
|
|
2015-04-27 04:44:32 -03:00
|
|
|
// locks onto a particular target sysid and sets it's position data stream to at least 1hz
|
2018-03-17 03:38:43 -03:00
|
|
|
void GCS_MAVLINK_Tracker::mavlink_check_target(const mavlink_message_t &msg)
|
2015-04-27 04:44:32 -03:00
|
|
|
{
|
|
|
|
// exit immediately if the target has already been set
|
2018-03-17 03:38:43 -03:00
|
|
|
if (tracker.target_set) {
|
2015-04-27 04:44:32 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// decode
|
|
|
|
mavlink_heartbeat_t packet;
|
2018-03-17 03:38:43 -03:00
|
|
|
mavlink_msg_heartbeat_decode(&msg, &packet);
|
2015-04-27 04:44:32 -03:00
|
|
|
|
|
|
|
// exit immediately if this is not a vehicle we would track
|
|
|
|
if ((packet.type == MAV_TYPE_ANTENNA_TRACKER) ||
|
|
|
|
(packet.type == MAV_TYPE_GCS) ||
|
|
|
|
(packet.type == MAV_TYPE_ONBOARD_CONTROLLER) ||
|
|
|
|
(packet.type == MAV_TYPE_GIMBAL)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set our sysid to the target, this ensures we lock onto a single vehicle
|
2018-03-17 03:38:43 -03:00
|
|
|
if (tracker.g.sysid_target == 0) {
|
2022-07-05 00:08:57 -03:00
|
|
|
tracker.g.sysid_target.set(msg.sysid);
|
2015-04-27 04:44:32 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// send data stream request to target on all channels
|
|
|
|
// Note: this doesn't check success for all sends meaning it's not guaranteed the vehicle's positions will be sent at 1hz
|
2018-03-17 03:38:43 -03:00
|
|
|
tracker.gcs().request_datastream_position(msg.sysid, msg.compid);
|
|
|
|
tracker.gcs().request_datastream_airpressure(msg.sysid, msg.compid);
|
2015-04-27 04:44:32 -03:00
|
|
|
|
|
|
|
// flag target has been set
|
2018-03-17 03:38:43 -03:00
|
|
|
tracker.target_set = true;
|
2015-04-27 04:44:32 -03:00
|
|
|
}
|
|
|
|
|
2017-07-12 04:51:08 -03:00
|
|
|
uint8_t GCS_MAVLINK_Tracker::sysid_my_gcs() const
|
|
|
|
{
|
|
|
|
return tracker.g.sysid_my_gcs;
|
|
|
|
}
|
|
|
|
|
2022-12-08 02:47:13 -04:00
|
|
|
MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro(const mavlink_message_t &msg)
|
2018-03-17 08:40:57 -03:00
|
|
|
{
|
2022-12-08 02:47:13 -04:00
|
|
|
MAV_RESULT ret = GCS_MAVLINK::_handle_command_preflight_calibration_baro(msg);
|
2018-03-18 01:15:13 -03:00
|
|
|
if (ret == MAV_RESULT_ACCEPTED) {
|
2018-03-17 08:40:57 -03:00
|
|
|
// zero the altitude difference on next baro update
|
|
|
|
tracker.nav_status.need_altitude_calibration = true;
|
|
|
|
}
|
2018-03-18 01:15:13 -03:00
|
|
|
return ret;
|
2018-03-17 08:40:57 -03:00
|
|
|
}
|
|
|
|
|
2023-05-02 09:22:25 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlink_command_int_t &packet)
|
2021-01-05 19:50:14 -04:00
|
|
|
{
|
|
|
|
if (is_equal(packet.param1,1.0f)) {
|
|
|
|
tracker.arm_servos();
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
if (is_zero(packet.param1)) {
|
|
|
|
tracker.disarm_servos();
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
|
2023-08-25 05:00:36 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
2018-07-03 23:23:52 -03:00
|
|
|
{
|
|
|
|
switch(packet.command) {
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SET_SERVO:
|
2019-09-13 12:41:55 -03:00
|
|
|
// ensure we are in servo test mode
|
|
|
|
tracker.set_mode(tracker.mode_servotest, ModeReason::SERVOTEST);
|
|
|
|
|
|
|
|
if (!tracker.mode_servotest.set_servo(packet.param1, packet.param2)) {
|
2018-07-03 23:23:52 -03:00
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
|
|
|
|
// mavproxy/mavutil sends this when auto command is entered
|
|
|
|
case MAV_CMD_MISSION_START:
|
2019-09-13 12:41:55 -03:00
|
|
|
tracker.set_mode(tracker.mode_auto, ModeReason::GCS_COMMAND);
|
2018-07-03 23:23:52 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
|
|
|
|
default:
|
2023-08-25 05:00:36 -03:00
|
|
|
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
2018-07-03 23:23:52 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-09-12 06:51:13 -03:00
|
|
|
bool GCS_MAVLINK_Tracker::set_home_to_current_location(bool _lock) {
|
2019-02-20 23:02:29 -04:00
|
|
|
return tracker.set_home(AP::gps().location());
|
|
|
|
}
|
2019-09-12 06:51:13 -03:00
|
|
|
bool GCS_MAVLINK_Tracker::set_home(const Location& loc, bool _lock) {
|
2019-02-20 23:02:29 -04:00
|
|
|
return tracker.set_home(loc);
|
|
|
|
}
|
|
|
|
|
2019-04-30 07:22:50 -03:00
|
|
|
void GCS_MAVLINK_Tracker::handleMessage(const mavlink_message_t &msg)
|
2014-12-09 23:32:30 -04:00
|
|
|
{
|
2019-04-30 07:22:50 -03:00
|
|
|
switch (msg.msgid) {
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2019-09-25 06:55:59 -03:00
|
|
|
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
|
|
|
|
handle_set_attitude_target(msg);
|
|
|
|
break;
|
|
|
|
|
2014-03-02 03:00:37 -04:00
|
|
|
// When mavproxy 'wp sethome'
|
|
|
|
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_mission_write_partial_list_t packet;
|
2019-04-30 07:22:50 -03:00
|
|
|
mavlink_msg_mission_write_partial_list_decode(&msg, &packet);
|
2014-03-02 03:00:37 -04:00
|
|
|
if (packet.start_index == 0)
|
|
|
|
{
|
|
|
|
// New home at wp index 0. Ask for it
|
|
|
|
waypoint_receiving = true;
|
2019-05-01 19:13:22 -03:00
|
|
|
send_message(MSG_NEXT_MISSION_REQUEST_WAYPOINTS);
|
2014-03-02 03:00:37 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// XXX receive a WP from GCS and store in EEPROM if it is HOME
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM:
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_mission_item_t packet;
|
2017-11-27 02:18:14 -04:00
|
|
|
MAV_MISSION_RESULT result = MAV_MISSION_ACCEPTED;
|
2014-03-02 03:00:37 -04:00
|
|
|
|
2019-04-30 07:22:50 -03:00
|
|
|
mavlink_msg_mission_item_decode(&msg, &packet);
|
2014-03-02 03:00:37 -04:00
|
|
|
|
2023-02-02 18:58:39 -04:00
|
|
|
Location tell_command;
|
2014-03-02 03:00:37 -04:00
|
|
|
|
|
|
|
switch (packet.frame)
|
|
|
|
{
|
|
|
|
case MAV_FRAME_MISSION:
|
|
|
|
case MAV_FRAME_GLOBAL:
|
|
|
|
{
|
2019-01-01 23:24:53 -04:00
|
|
|
tell_command = Location{
|
|
|
|
int32_t(1.0e7f*packet.x), // in as DD converted to * t7
|
|
|
|
int32_t(1.0e7f*packet.y), // in as DD converted to * t7
|
|
|
|
int32_t(packet.z*1.0e2f), // in as m converted to cm
|
2019-03-14 22:44:11 -03:00
|
|
|
Location::AltFrame::ABSOLUTE
|
2019-01-01 23:24:53 -04:00
|
|
|
};
|
2014-03-02 03:00:37 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
#ifdef MAV_FRAME_LOCAL_NED
|
|
|
|
case MAV_FRAME_LOCAL_NED: // local (relative to home position)
|
|
|
|
{
|
2019-01-01 23:24:53 -04:00
|
|
|
tell_command = Location{
|
|
|
|
int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat),
|
|
|
|
int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng),
|
|
|
|
int32_t(-packet.z*1.0e2f),
|
2019-03-14 22:44:11 -03:00
|
|
|
Location::AltFrame::ABOVE_HOME
|
2019-01-01 23:24:53 -04:00
|
|
|
};
|
2014-03-02 03:00:37 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifdef MAV_FRAME_LOCAL
|
|
|
|
case MAV_FRAME_LOCAL: // local (relative to home position)
|
|
|
|
{
|
2019-01-01 23:24:53 -04:00
|
|
|
tell_command = {
|
|
|
|
int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat),
|
|
|
|
int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng),
|
|
|
|
int32_t(packet.z*1.0e2f),
|
2019-03-14 22:44:11 -03:00
|
|
|
Location::AltFrame::ABOVE_HOME
|
2019-01-01 23:24:53 -04:00
|
|
|
};
|
2014-03-02 03:00:37 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude
|
|
|
|
{
|
2019-01-01 23:24:53 -04:00
|
|
|
tell_command = {
|
|
|
|
int32_t(1.0e7f * packet.x), // in as DD converted to * t7
|
|
|
|
int32_t(1.0e7f * packet.y), // in as DD converted to * t7
|
|
|
|
int32_t(packet.z * 1.0e2f),
|
2019-03-14 22:44:11 -03:00
|
|
|
Location::AltFrame::ABOVE_HOME
|
2019-01-01 23:24:53 -04:00
|
|
|
};
|
2014-03-02 03:00:37 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
default:
|
|
|
|
result = MAV_MISSION_UNSUPPORTED_FRAME;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (result != MAV_MISSION_ACCEPTED) goto mission_failed;
|
|
|
|
|
|
|
|
// Check if receiving waypoints (mission upload expected)
|
|
|
|
if (!waypoint_receiving) {
|
|
|
|
result = MAV_MISSION_ERROR;
|
|
|
|
goto mission_failed;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if this is the HOME wp
|
|
|
|
if (packet.seq == 0) {
|
2019-02-20 21:43:55 -04:00
|
|
|
if (!tracker.set_home(tell_command)) {
|
|
|
|
result = MAV_MISSION_ERROR;
|
|
|
|
goto mission_failed;
|
|
|
|
}
|
2015-11-18 14:47:45 -04:00
|
|
|
send_text(MAV_SEVERITY_INFO,"New HOME received");
|
2014-03-02 03:00:37 -04:00
|
|
|
waypoint_receiving = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
mission_failed:
|
|
|
|
// we are rejecting the mission/waypoint
|
|
|
|
mavlink_msg_mission_ack_send(
|
|
|
|
chan,
|
2019-04-30 07:22:50 -03:00
|
|
|
msg.sysid,
|
|
|
|
msg.compid,
|
2017-04-11 08:43:56 -03:00
|
|
|
result,
|
|
|
|
MAV_MISSION_TYPE_MISSION);
|
2014-03-02 03:00:37 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2014-03-15 19:17:04 -03:00
|
|
|
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
|
|
|
{
|
|
|
|
mavlink_manual_control_t packet;
|
2019-04-30 07:22:50 -03:00
|
|
|
mavlink_msg_manual_control_decode(&msg, &packet);
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.tracking_manual_control(packet);
|
2014-03-15 19:17:04 -03:00
|
|
|
break;
|
|
|
|
}
|
2014-03-02 03:00:37 -04:00
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
|
|
|
|
{
|
2013-10-13 04:14:13 -03:00
|
|
|
// decode
|
|
|
|
mavlink_global_position_int_t packet;
|
2019-04-30 07:22:50 -03:00
|
|
|
mavlink_msg_global_position_int_decode(&msg, &packet);
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.tracking_update_position(packet);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2014-03-12 00:36:51 -03:00
|
|
|
case MAVLINK_MSG_ID_SCALED_PRESSURE:
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_scaled_pressure_t packet;
|
2019-04-30 07:22:50 -03:00
|
|
|
mavlink_msg_scaled_pressure_decode(&msg, &packet);
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.tracking_update_pressure(packet);
|
2014-03-12 00:36:51 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-11-06 20:06:43 -04:00
|
|
|
default:
|
|
|
|
handle_common_message(msg);
|
2016-01-20 22:50:48 -04:00
|
|
|
break;
|
2013-10-13 04:14:13 -03:00
|
|
|
} // end switch
|
|
|
|
} // end handle mavlink
|
|
|
|
|
|
|
|
|
2019-02-28 17:38:28 -04:00
|
|
|
// send position tracker is using
|
|
|
|
void GCS_MAVLINK_Tracker::send_global_position_int()
|
|
|
|
{
|
|
|
|
if (!tracker.stationary) {
|
|
|
|
GCS_MAVLINK::send_global_position_int();
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_msg_global_position_int_send(
|
|
|
|
chan,
|
|
|
|
AP_HAL::millis(),
|
|
|
|
tracker.current_loc.lat, // in 1E7 degrees
|
|
|
|
tracker.current_loc.lng, // in 1E7 degrees
|
|
|
|
tracker.current_loc.alt, // millimeters above ground/sea level
|
|
|
|
0, // millimeters above home
|
|
|
|
0, // X speed cm/s (+ve North)
|
|
|
|
0, // Y speed cm/s (+ve East)
|
|
|
|
0, // Z speed cm/s (+ve Down)
|
|
|
|
tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree
|
|
|
|
}
|