2016-05-27 10:14:08 -03:00
|
|
|
#include "GCS_Mavlink.h"
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
#include "Tracker.h"
|
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
// default sensors are present and healthy: gyro, accelerometer, barometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control
|
|
|
|
#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE | 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)
|
|
|
|
|
|
|
|
/*
|
|
|
|
* !!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
|
|
|
|
*/
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::send_heartbeat(mavlink_channel_t chan)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2014-03-06 18:13:53 -04:00
|
|
|
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
|
|
|
uint8_t system_status = MAV_STATE_ACTIVE;
|
|
|
|
uint32_t custom_mode = control_mode;
|
|
|
|
|
|
|
|
// 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 (control_mode) {
|
|
|
|
case MANUAL:
|
2014-03-12 00:36:51 -03:00
|
|
|
base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
2014-03-06 18:13:53 -04:00
|
|
|
break;
|
|
|
|
|
2014-03-22 05:08:17 -03:00
|
|
|
case STOP:
|
|
|
|
break;
|
|
|
|
|
2014-04-09 02:27:56 -03:00
|
|
|
case SCAN:
|
2014-10-06 08:45:07 -03:00
|
|
|
case SERVO_TEST:
|
2014-03-06 18:13:53 -04:00
|
|
|
case AUTO:
|
2014-03-12 00:36:51 -03:00
|
|
|
base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED |
|
|
|
|
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;
|
|
|
|
|
|
|
|
case INITIALISING:
|
|
|
|
system_status = MAV_STATE_CALIBRATING;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-07-05 23:09:09 -03:00
|
|
|
// we are armed if safety switch is not disarmed
|
|
|
|
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
|
|
|
|
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
|
|
|
}
|
|
|
|
|
2017-02-13 21:30:32 -04:00
|
|
|
gcs().chan(chan-MAVLINK_COMM_0).send_heartbeat(MAV_TYPE_ANTENNA_TRACKER,
|
2016-05-16 19:43:41 -03:00
|
|
|
base_mode,
|
|
|
|
custom_mode,
|
|
|
|
system_status);
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::send_attitude(mavlink_channel_t chan)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
|
|
|
Vector3f omega = ahrs.get_gyro();
|
|
|
|
mavlink_msg_attitude_send(
|
|
|
|
chan,
|
2015-11-19 23:04:37 -04:00
|
|
|
AP_HAL::millis(),
|
2013-10-13 04:14:13 -03:00
|
|
|
ahrs.roll,
|
|
|
|
ahrs.pitch,
|
|
|
|
ahrs.yaw,
|
|
|
|
omega.x,
|
|
|
|
omega.y,
|
|
|
|
omega.z);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2017-11-26 21:51:11 -04:00
|
|
|
void Tracker::send_extended_status1(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
int16_t battery_current = -1;
|
|
|
|
int8_t battery_remaining = -1;
|
|
|
|
|
|
|
|
if (battery.has_current() && battery.healthy()) {
|
|
|
|
battery_remaining = battery.capacity_remaining_pct();
|
|
|
|
battery_current = battery.current_amps() * 100;
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_msg_sys_status_send(
|
|
|
|
chan,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
static_cast<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);
|
|
|
|
}
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::send_location(mavlink_channel_t chan)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
|
|
|
uint32_t fix_time;
|
2014-03-31 04:32:14 -03:00
|
|
|
if (gps.status() >= AP_GPS::GPS_OK_FIX_2D) {
|
|
|
|
fix_time = gps.last_fix_time_ms();
|
2013-10-13 04:14:13 -03:00
|
|
|
} else {
|
2015-11-19 23:04:37 -04:00
|
|
|
fix_time = AP_HAL::millis();
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
2014-03-31 04:32:14 -03:00
|
|
|
const Vector3f &vel = gps.velocity();
|
2013-10-13 04:14:13 -03:00
|
|
|
mavlink_msg_global_position_int_send(
|
|
|
|
chan,
|
|
|
|
fix_time,
|
2014-03-02 03:00:37 -04:00
|
|
|
current_loc.lat, // in 1E7 degrees
|
|
|
|
current_loc.lng, // in 1E7 degrees
|
|
|
|
current_loc.alt * 10, // millimeters above sea level
|
2013-10-13 04:14:13 -03:00
|
|
|
0,
|
2014-03-31 04:32:14 -03:00
|
|
|
vel.x * 100, // X speed cm/s (+ve North)
|
|
|
|
vel.y * 100, // Y speed cm/s (+ve East)
|
|
|
|
vel.z * -100, // Z speed cm/s (+ve up)
|
2013-10-13 04:14:13 -03:00
|
|
|
ahrs.yaw_sensor);
|
|
|
|
}
|
|
|
|
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::send_nav_controller_output(mavlink_channel_t chan)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2016-06-13 05:44:23 -03:00
|
|
|
float alt_diff = (g.alt_source == ALT_SOURCE_BARO) ? nav_status.alt_difference_baro : 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,
|
|
|
|
nav_status.pitch,
|
|
|
|
nav_status.bearing,
|
|
|
|
nav_status.bearing,
|
2017-06-19 02:40:19 -03:00
|
|
|
MIN(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);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2014-03-12 17:30:25 -03:00
|
|
|
// report simulator state
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::send_simstate(mavlink_channel_t chan)
|
2014-03-12 17:30:25 -03:00
|
|
|
{
|
2015-05-04 03:18:37 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2014-03-12 17:30:25 -03:00
|
|
|
sitl.simstate_send(chan);
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
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
|
|
|
}
|
|
|
|
|
2016-05-27 10:14:08 -03:00
|
|
|
void GCS_MAVLINK_Tracker::handle_change_alt_request(AP_Mission::Mission_Command&)
|
2015-08-15 07:43:48 -03:00
|
|
|
{
|
|
|
|
// do nothing
|
|
|
|
}
|
2014-03-12 17:30:25 -03:00
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
// try to send a message, return false if it won't fit in the serial tx buffer
|
2016-05-27 10:14:08 -03:00
|
|
|
bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
|
|
|
switch (id) {
|
|
|
|
case MSG_HEARTBEAT:
|
|
|
|
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
2016-05-16 19:27:01 -03:00
|
|
|
last_heartbeat_time = AP_HAL::millis();
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.send_heartbeat(chan);
|
2013-10-13 04:14:13 -03:00
|
|
|
return true;
|
|
|
|
|
|
|
|
case MSG_ATTITUDE:
|
|
|
|
CHECK_PAYLOAD_SIZE(ATTITUDE);
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.send_attitude(chan);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_LOCATION:
|
|
|
|
CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.send_location(chan);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
|
2015-04-06 19:29:47 -03:00
|
|
|
case MSG_LOCAL_POSITION:
|
|
|
|
CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
|
2015-06-01 02:04:25 -03:00
|
|
|
send_local_position(tracker.ahrs);
|
2015-04-06 19:29:47 -03:00
|
|
|
break;
|
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
case MSG_NAV_CONTROLLER_OUTPUT:
|
|
|
|
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.send_nav_controller_output(chan);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
|
2014-10-06 05:51:42 -03:00
|
|
|
case MSG_RADIO_IN:
|
2016-10-13 07:24:09 -03:00
|
|
|
CHECK_PAYLOAD_SIZE(RC_CHANNELS);
|
2016-05-16 19:27:01 -03:00
|
|
|
send_radio_in(0);
|
2014-10-06 05:51:42 -03:00
|
|
|
break;
|
|
|
|
|
2017-01-10 11:19:42 -04:00
|
|
|
case MSG_SERVO_OUTPUT_RAW:
|
2013-10-13 04:14:13 -03:00
|
|
|
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
|
2016-07-15 07:04:19 -03:00
|
|
|
send_servo_output_raw(false);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_RAW_IMU1:
|
|
|
|
CHECK_PAYLOAD_SIZE(RAW_IMU);
|
2016-05-16 19:27:01 -03:00
|
|
|
send_raw_imu(tracker.ins, tracker.compass);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_RAW_IMU2:
|
|
|
|
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
2016-05-16 19:27:01 -03:00
|
|
|
send_scaled_pressure(tracker.barometer);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_RAW_IMU3:
|
|
|
|
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
2016-05-16 19:27:01 -03:00
|
|
|
send_sensor_offsets(tracker.ins, tracker.compass, tracker.barometer);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_AHRS:
|
|
|
|
CHECK_PAYLOAD_SIZE(AHRS);
|
2016-05-16 19:27:01 -03:00
|
|
|
send_ahrs(tracker.ahrs);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
|
2014-03-12 17:30:25 -03:00
|
|
|
case MSG_SIMSTATE:
|
|
|
|
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.send_simstate(chan);
|
2014-03-12 17:30:25 -03:00
|
|
|
break;
|
|
|
|
|
2017-11-26 21:51:11 -04:00
|
|
|
case MSG_EXTENDED_STATUS1:
|
|
|
|
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
|
|
|
tracker.send_extended_status1(chan);
|
|
|
|
break;
|
|
|
|
|
2017-07-18 03:39:57 -03:00
|
|
|
default:
|
|
|
|
return GCS_MAVLINK::try_send_message(id);
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
default stream rates to 1Hz
|
|
|
|
*/
|
2015-10-25 14:03:46 -03:00
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK::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
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRates[0], 1),
|
|
|
|
|
|
|
|
// @Param: EXT_STAT
|
|
|
|
// @DisplayName: Extended status stream rate to ground station
|
|
|
|
// @Description: Extended status stream rate to ground station
|
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRates[1], 1),
|
|
|
|
|
|
|
|
// @Param: RC_CHAN
|
|
|
|
// @DisplayName: RC Channel stream rate to ground station
|
|
|
|
// @Description: RC Channel stream rate to ground station
|
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRates[2], 1),
|
|
|
|
|
|
|
|
// @Param: RAW_CTRL
|
|
|
|
// @DisplayName: Raw Control stream rate to ground station
|
|
|
|
// @Description: Raw Control stream rate to ground station
|
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK, streamRates[3], 1),
|
|
|
|
|
|
|
|
// @Param: POSITION
|
|
|
|
// @DisplayName: Position stream rate to ground station
|
|
|
|
// @Description: Position stream rate to ground station
|
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRates[4], 1),
|
|
|
|
|
|
|
|
// @Param: EXTRA1
|
|
|
|
// @DisplayName: Extra data type 1 stream rate to ground station
|
|
|
|
// @Description: Extra data type 1 stream rate to ground station
|
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRates[5], 1),
|
|
|
|
|
|
|
|
// @Param: EXTRA2
|
|
|
|
// @DisplayName: Extra data type 2 stream rate to ground station
|
|
|
|
// @Description: Extra data type 2 stream rate to ground station
|
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRates[6], 1),
|
|
|
|
|
|
|
|
// @Param: EXTRA3
|
|
|
|
// @DisplayName: Extra data type 3 stream rate to ground station
|
|
|
|
// @Description: Extra data type 3 stream rate to ground station
|
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRates[7], 1),
|
|
|
|
|
|
|
|
// @Param: PARAMS
|
|
|
|
// @DisplayName: Parameter stream rate to ground station
|
|
|
|
// @Description: Parameter stream rate to ground station
|
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 10),
|
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
|
|
|
void
|
2016-05-27 10:14:08 -03:00
|
|
|
GCS_MAVLINK_Tracker::data_stream_send(void)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2017-04-29 01:36:42 -03:00
|
|
|
send_queued_parameters();
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2015-12-27 03:05:14 -04:00
|
|
|
if (tracker.in_mavlink_delay) {
|
2013-10-13 04:14:13 -03:00
|
|
|
// don't send any other stream types while in the delay callback
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2017-06-18 19:18:18 -03:00
|
|
|
if (!tracker.in_mavlink_delay) {
|
|
|
|
tracker.DataFlash.handle_log_send(*this);
|
|
|
|
}
|
|
|
|
|
2013-10-13 04:14:13 -03:00
|
|
|
if (stream_trigger(STREAM_RAW_SENSORS)) {
|
|
|
|
send_message(MSG_RAW_IMU1);
|
|
|
|
send_message(MSG_RAW_IMU2);
|
|
|
|
send_message(MSG_RAW_IMU3);
|
|
|
|
}
|
|
|
|
|
|
|
|
if (stream_trigger(STREAM_EXTENDED_STATUS)) {
|
|
|
|
send_message(MSG_EXTENDED_STATUS1);
|
|
|
|
send_message(MSG_EXTENDED_STATUS2);
|
|
|
|
send_message(MSG_NAV_CONTROLLER_OUTPUT);
|
|
|
|
send_message(MSG_GPS_RAW);
|
2017-08-08 07:01:42 -03:00
|
|
|
send_message(MSG_GPS_RTK);
|
|
|
|
send_message(MSG_GPS2_RAW);
|
|
|
|
send_message(MSG_GPS2_RTK);
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (stream_trigger(STREAM_POSITION)) {
|
|
|
|
send_message(MSG_LOCATION);
|
2015-04-06 19:29:47 -03:00
|
|
|
send_message(MSG_LOCAL_POSITION);
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
|
2017-11-26 21:51:31 -04:00
|
|
|
send_message(MSG_SERVO_OUTPUT_RAW);
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (stream_trigger(STREAM_RC_CHANNELS)) {
|
2014-10-06 05:51:42 -03:00
|
|
|
send_message(MSG_RADIO_IN);
|
2017-01-10 11:19:42 -04:00
|
|
|
send_message(MSG_SERVO_OUTPUT_RAW);
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (stream_trigger(STREAM_EXTRA1)) {
|
|
|
|
send_message(MSG_ATTITUDE);
|
|
|
|
}
|
|
|
|
|
|
|
|
if (stream_trigger(STREAM_EXTRA3)) {
|
|
|
|
send_message(MSG_AHRS);
|
|
|
|
send_message(MSG_HWSTATUS);
|
2014-03-12 17:30:25 -03:00
|
|
|
send_message(MSG_SIMSTATE);
|
2015-07-31 02:52:02 -03:00
|
|
|
send_message(MSG_MAG_CAL_REPORT);
|
|
|
|
send_message(MSG_MAG_CAL_PROGRESS);
|
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
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::mavlink_snoop(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
|
|
|
|
if ((g.sysid_target != 0) && (g.sysid_target != msg->sysid)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-12-09 23:32:30 -04: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;
|
|
|
|
mavlink_msg_global_position_int_decode(msg, &packet);
|
|
|
|
tracking_update_position(packet);
|
|
|
|
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;
|
|
|
|
mavlink_msg_scaled_pressure_decode(msg, &packet);
|
|
|
|
tracking_update_pressure(packet);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
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
|
2015-06-01 02:04:25 -03:00
|
|
|
void 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
|
|
|
|
if (target_set) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// decode
|
|
|
|
mavlink_heartbeat_t packet;
|
|
|
|
mavlink_msg_heartbeat_decode(msg, &packet);
|
|
|
|
|
|
|
|
// 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
|
|
|
|
if (g.sysid_target == 0) {
|
|
|
|
g.sysid_target = msg->sysid;
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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
|
2017-02-13 21:30:32 -04:00
|
|
|
gcs().request_datastream_position(msg->sysid, msg->compid);
|
|
|
|
gcs().request_datastream_airpressure(msg->sysid, msg->compid);
|
2015-04-27 04:44:32 -03:00
|
|
|
|
|
|
|
// flag target has been set
|
|
|
|
target_set = true;
|
|
|
|
}
|
|
|
|
|
2017-07-12 04:51:08 -03:00
|
|
|
uint8_t GCS_MAVLINK_Tracker::sysid_my_gcs() const
|
|
|
|
{
|
|
|
|
return tracker.g.sysid_my_gcs;
|
|
|
|
}
|
|
|
|
|
2016-05-27 10:14:08 -03:00
|
|
|
void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
2014-12-09 23:32:30 -04:00
|
|
|
{
|
2013-10-13 04:14:13 -03:00
|
|
|
switch (msg->msgid) {
|
|
|
|
|
2014-05-13 23:11:22 -03:00
|
|
|
// If we are currently operating as a proxy for a remote,
|
2016-09-16 22:43:32 -03:00
|
|
|
// alas we have to look inside each packet to see if it's for us or for the remote
|
2013-10-13 04:14:13 -03:00
|
|
|
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
|
|
|
{
|
2016-02-09 21:50:19 -04:00
|
|
|
handle_request_data_stream(msg, false);
|
2013-10-13 04:14:13 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT:
|
|
|
|
break;
|
|
|
|
|
2014-03-02 03:00:37 -04:00
|
|
|
case MAVLINK_MSG_ID_COMMAND_LONG:
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_command_long_t packet;
|
|
|
|
mavlink_msg_command_long_decode(msg, &packet);
|
|
|
|
|
|
|
|
uint8_t result = MAV_RESULT_UNSUPPORTED;
|
|
|
|
|
|
|
|
// do command
|
2015-11-18 14:47:45 -04:00
|
|
|
send_text(MAV_SEVERITY_INFO,"Command received: ");
|
2014-03-02 03:00:37 -04:00
|
|
|
|
|
|
|
switch(packet.command) {
|
|
|
|
|
|
|
|
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
|
|
|
{
|
2015-05-04 23:34:15 -03:00
|
|
|
if (is_equal(packet.param1,1.0f)) {
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.ins.init_gyro();
|
|
|
|
if (tracker.ins.gyro_calibrated_ok_all()) {
|
|
|
|
tracker.ahrs.reset_gyro_drift();
|
2015-03-10 20:17:22 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
} else {
|
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
}
|
2016-08-07 23:52:40 -03:00
|
|
|
}
|
2015-05-04 23:34:15 -03:00
|
|
|
if (is_equal(packet.param3,1.0f)) {
|
2016-05-23 22:31:41 -03:00
|
|
|
tracker.init_barometer(false);
|
2014-04-09 01:29:23 -03:00
|
|
|
// zero the altitude difference on next baro update
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.nav_status.need_altitude_calibration = true;
|
2016-08-07 23:52:24 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2014-03-02 03:00:37 -04:00
|
|
|
}
|
2015-05-04 23:34:15 -03:00
|
|
|
if (is_equal(packet.param4,1.0f)) {
|
2016-05-12 14:06:58 -03:00
|
|
|
// Can't trim radio
|
2016-08-07 23:52:24 -03:00
|
|
|
result = MAV_RESULT_UNSUPPORTED;
|
2015-05-15 18:28:50 -03:00
|
|
|
} else if (is_equal(packet.param5,1.0f)) {
|
2015-10-21 18:27:35 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2015-09-21 00:10:19 -03:00
|
|
|
// start with gyro calibration
|
|
|
|
tracker.ins.init_gyro();
|
|
|
|
// reset ahrs gyro bias
|
|
|
|
if (tracker.ins.gyro_calibrated_ok_all()) {
|
|
|
|
tracker.ahrs.reset_gyro_drift();
|
2015-10-21 18:27:35 -03:00
|
|
|
} else {
|
|
|
|
result = MAV_RESULT_FAILED;
|
2015-09-21 00:10:19 -03:00
|
|
|
}
|
2015-10-21 18:27:35 -03:00
|
|
|
// start accel cal
|
|
|
|
tracker.ins.acal_init();
|
|
|
|
tracker.ins.get_acal()->start(this);
|
2015-05-15 18:28:50 -03:00
|
|
|
} else if (is_equal(packet.param5,2.0f)) {
|
2015-09-21 00:10:19 -03:00
|
|
|
// start with gyro calibration
|
|
|
|
tracker.ins.init_gyro();
|
2015-05-15 18:28:50 -03:00
|
|
|
// accel trim
|
|
|
|
float trim_roll, trim_pitch;
|
2016-08-07 23:52:40 -03:00
|
|
|
if (tracker.ins.calibrate_trim(trim_roll, trim_pitch)) {
|
2015-05-15 18:28:50 -03:00
|
|
|
// reset ahrs's trim to suggested values from calibration routine
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
2015-05-15 18:28:50 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
} else {
|
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
}
|
2014-03-02 03:00:37 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2014-03-06 18:13:53 -04:00
|
|
|
case MAV_CMD_COMPONENT_ARM_DISARM:
|
|
|
|
if (packet.target_component == MAV_COMP_ID_SYSTEM_CONTROL) {
|
2015-05-04 23:34:15 -03:00
|
|
|
if (is_equal(packet.param1,1.0f)) {
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.arm_servos();
|
2014-03-06 18:13:53 -04:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2015-05-04 23:34:15 -03:00
|
|
|
} else if (is_zero(packet.param1)) {
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.disarm_servos();
|
2014-03-06 18:13:53 -04:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
} else {
|
|
|
|
result = MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
2014-03-03 20:37:15 -04:00
|
|
|
} else {
|
|
|
|
result = MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
break;
|
2014-10-06 08:45:07 -03:00
|
|
|
|
2015-10-02 08:53:28 -03:00
|
|
|
case MAV_CMD_GET_HOME_POSITION:
|
|
|
|
send_home(tracker.ahrs.get_home());
|
2017-09-18 02:38:26 -03:00
|
|
|
Location ekf_origin;
|
|
|
|
if (tracker.ahrs.get_origin(ekf_origin)) {
|
|
|
|
send_ekf_origin(ekf_origin);
|
|
|
|
}
|
2015-12-06 22:30:56 -04:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2015-10-02 08:53:28 -03:00
|
|
|
break;
|
|
|
|
|
2014-10-06 08:45:07 -03:00
|
|
|
case MAV_CMD_DO_SET_SERVO:
|
2015-06-01 02:04:25 -03:00
|
|
|
if (tracker.servo_test_set_servo(packet.param1, packet.param2)) {
|
2014-10-06 08:45:07 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2014-03-06 18:13:53 -04:00
|
|
|
// mavproxy/mavutil sends this when auto command is entered
|
|
|
|
case MAV_CMD_MISSION_START:
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.set_mode(AUTO);
|
2014-03-06 18:13:53 -04:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
break;
|
2014-03-03 20:37:15 -04:00
|
|
|
|
2014-03-02 03:00:37 -04:00
|
|
|
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
|
|
|
{
|
2015-05-04 23:34:15 -03:00
|
|
|
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
|
2014-03-02 03:00:37 -04:00
|
|
|
// when packet.param1 == 3 we reboot to hold in bootloader
|
2015-05-04 23:34:15 -03:00
|
|
|
hal.scheduler->reboot(is_equal(packet.param1,3.0f));
|
2014-03-02 03:00:37 -04:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-11-12 05:49:46 -04:00
|
|
|
case MAV_CMD_ACCELCAL_VEHICLE_POS:
|
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
|
|
|
|
if (tracker.ins.get_acal()->gcs_vehicle_position(packet.param1)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2014-03-02 03:00:37 -04:00
|
|
|
default:
|
2017-07-13 23:04:53 -03:00
|
|
|
result = handle_command_long_message(packet);
|
2014-03-02 03:00:37 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
mavlink_msg_command_ack_send(
|
|
|
|
chan,
|
|
|
|
packet.command,
|
|
|
|
result);
|
|
|
|
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// When mavproxy 'wp sethome'
|
|
|
|
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_mission_write_partial_list_t packet;
|
|
|
|
mavlink_msg_mission_write_partial_list_decode(msg, &packet);
|
|
|
|
if (packet.start_index == 0)
|
|
|
|
{
|
|
|
|
// New home at wp index 0. Ask for it
|
|
|
|
waypoint_receiving = true;
|
|
|
|
waypoint_request_i = 0;
|
|
|
|
waypoint_request_last = 0;
|
|
|
|
send_message(MSG_NEXT_WAYPOINT);
|
|
|
|
}
|
|
|
|
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;
|
|
|
|
uint8_t result = MAV_MISSION_ACCEPTED;
|
|
|
|
|
|
|
|
mavlink_msg_mission_item_decode(msg, &packet);
|
|
|
|
|
|
|
|
struct Location tell_command = {};
|
|
|
|
|
|
|
|
switch (packet.frame)
|
|
|
|
{
|
|
|
|
case MAV_FRAME_MISSION:
|
|
|
|
case MAV_FRAME_GLOBAL:
|
|
|
|
{
|
|
|
|
tell_command.lat = 1.0e7f*packet.x; // in as DD converted to * t7
|
|
|
|
tell_command.lng = 1.0e7f*packet.y; // in as DD converted to * t7
|
|
|
|
tell_command.alt = packet.z*1.0e2f; // in as m converted to cm
|
|
|
|
tell_command.options = 0; // absolute altitude
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
#ifdef MAV_FRAME_LOCAL_NED
|
|
|
|
case MAV_FRAME_LOCAL_NED: // local (relative to home position)
|
|
|
|
{
|
|
|
|
tell_command.lat = 1.0e7f*ToDeg(packet.x/
|
|
|
|
(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat;
|
|
|
|
tell_command.lng = 1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng;
|
|
|
|
tell_command.alt = -packet.z*1.0e2f;
|
|
|
|
tell_command.options = MASK_OPTIONS_RELATIVE_ALT;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifdef MAV_FRAME_LOCAL
|
|
|
|
case MAV_FRAME_LOCAL: // local (relative to home position)
|
|
|
|
{
|
|
|
|
tell_command.lat = 1.0e7f*ToDeg(packet.x/
|
|
|
|
(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat;
|
|
|
|
tell_command.lng = 1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng;
|
|
|
|
tell_command.alt = packet.z*1.0e2f;
|
|
|
|
tell_command.options = MASK_OPTIONS_RELATIVE_ALT;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude
|
|
|
|
{
|
|
|
|
tell_command.lat = 1.0e7f * packet.x; // in as DD converted to * t7
|
|
|
|
tell_command.lng = 1.0e7f * packet.y; // in as DD converted to * t7
|
|
|
|
tell_command.alt = packet.z * 1.0e2f;
|
|
|
|
tell_command.options = MASK_OPTIONS_RELATIVE_ALT; // store altitude relative!! Always!!
|
|
|
|
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) {
|
2015-06-01 02:04:25 -03:00
|
|
|
tracker.set_home(tell_command); // New home in EEPROM
|
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,
|
|
|
|
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;
|
|
|
|
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;
|
|
|
|
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;
|
|
|
|
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
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
* 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
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::mavlink_delay_cb()
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
|
|
|
static uint32_t last_1hz, last_50hz, last_5s;
|
2017-02-13 21:30:32 -04:00
|
|
|
if (!gcs().chan(0).initialised) {
|
|
|
|
return;
|
|
|
|
}
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2015-12-27 03:05:14 -04:00
|
|
|
tracker.in_mavlink_delay = true;
|
2017-06-14 23:08:27 -03:00
|
|
|
DataFlash.EnableWrites(false);
|
2013-10-13 04:14:13 -03:00
|
|
|
|
2015-11-19 23:04:37 -04:00
|
|
|
uint32_t tnow = AP_HAL::millis();
|
2013-10-13 04:14:13 -03:00
|
|
|
if (tnow - last_1hz > 1000) {
|
|
|
|
last_1hz = tnow;
|
2017-07-07 23:02:52 -03:00
|
|
|
gcs().send_message(MSG_HEARTBEAT);
|
|
|
|
gcs().send_message(MSG_EXTENDED_STATUS1);
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
if (tnow - last_50hz > 20) {
|
|
|
|
last_50hz = tnow;
|
|
|
|
gcs_update();
|
|
|
|
gcs_data_stream_send();
|
|
|
|
notify.update();
|
|
|
|
}
|
|
|
|
if (tnow - last_5s > 5000) {
|
|
|
|
last_5s = tnow;
|
2017-07-08 21:28:33 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
2017-06-14 23:08:27 -03:00
|
|
|
DataFlash.EnableWrites(true);
|
2015-12-27 03:05:14 -04:00
|
|
|
tracker.in_mavlink_delay = false;
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* send data streams in the given rate range on both links
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::gcs_data_stream_send(void)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2017-02-13 21:30:32 -04:00
|
|
|
gcs().data_stream_send();
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
* look for incoming commands on the GCS links
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::gcs_update(void)
|
2013-10-13 04:14:13 -03:00
|
|
|
{
|
2017-02-13 21:30:32 -04:00
|
|
|
gcs().update();
|
2013-10-13 04:14:13 -03:00
|
|
|
}
|
|
|
|
|
2014-02-18 03:55:32 -04:00
|
|
|
/**
|
|
|
|
retry any deferred messages
|
|
|
|
*/
|
2015-06-01 02:04:25 -03:00
|
|
|
void Tracker::gcs_retry_deferred(void)
|
2014-02-18 03:55:32 -04:00
|
|
|
{
|
2017-07-18 22:37:13 -03:00
|
|
|
gcs().retry_deferred();
|
2014-02-18 03:55:32 -04:00
|
|
|
}
|
2017-07-16 21:47:16 -03:00
|
|
|
|
|
|
|
Compass *GCS_MAVLINK_Tracker::get_compass() const
|
|
|
|
{
|
|
|
|
return &tracker.compass;
|
|
|
|
}
|
2017-07-26 03:35:27 -03:00
|
|
|
|
2017-08-11 03:15:34 -03:00
|
|
|
/*
|
|
|
|
set_mode() wrapper for MAVLink SET_MODE
|
|
|
|
*/
|
|
|
|
bool GCS_MAVLINK_Tracker::set_mode(uint8_t mode)
|
|
|
|
{
|
|
|
|
switch (mode) {
|
|
|
|
case AUTO:
|
|
|
|
case MANUAL:
|
|
|
|
case SCAN:
|
|
|
|
case SERVO_TEST:
|
|
|
|
case STOP:
|
|
|
|
tracker.set_mode((enum ControlMode)mode);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-08-19 06:53:15 -03:00
|
|
|
const AP_FWVersion &GCS_MAVLINK_Tracker::get_fwver() const
|
|
|
|
{
|
|
|
|
return tracker.fwver;
|
|
|
|
}
|
|
|
|
|
2017-09-18 23:42:32 -03:00
|
|
|
void GCS_MAVLINK_Tracker::set_ekf_origin(const Location& loc)
|
|
|
|
{
|
|
|
|
tracker.set_ekf_origin(loc);
|
|
|
|
}
|
|
|
|
|
2017-07-26 03:35:27 -03:00
|
|
|
/* dummy methods to avoid having to link against AP_Camera */
|
|
|
|
void AP_Camera::control_msg(mavlink_message_t const*) {}
|
|
|
|
void AP_Camera::configure(float, float, float, float, float, float, float) {}
|
|
|
|
void AP_Camera::control(float, float, float, float, float, float) {}
|
2017-08-04 13:30:22 -03:00
|
|
|
void AP_Camera::send_feedback(mavlink_channel_t chan) {}
|
2017-07-26 03:35:27 -03:00
|
|
|
/* end dummy methods to avoid having to link against AP_Camera */
|
2017-07-27 02:23:00 -03:00
|
|
|
|
|
|
|
// dummy method to avoid linking AFS
|
|
|
|
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) {return false;}
|