mirror of https://github.com/ArduPilot/ardupilot
682 lines
21 KiB
C++
682 lines
21 KiB
C++
#include "GCS_Mavlink.h"
|
|
|
|
#include "Tracker.h"
|
|
|
|
// 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
|
|
*/
|
|
|
|
MAV_TYPE GCS_MAVLINK_Tracker::frame_type() const
|
|
{
|
|
return MAV_TYPE_ANTENNA_TRACKER;
|
|
}
|
|
|
|
MAV_MODE GCS_MAVLINK_Tracker::base_mode() const
|
|
{
|
|
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
|
// work out the base_mode. This value is not very useful
|
|
// for APM, but we calculate it as best we can so a generic
|
|
// MAVLink enabled ground station can work out something about
|
|
// what the MAV is up to. The actual bit values are highly
|
|
// ambiguous for most of the APM flight modes. In practice, you
|
|
// only get useful information from the custom_mode, which maps to
|
|
// the APM flight mode and has a well defined meaning in the
|
|
// ArduPlane documentation
|
|
switch (tracker.control_mode) {
|
|
case MANUAL:
|
|
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
|
break;
|
|
|
|
case STOP:
|
|
break;
|
|
|
|
case SCAN:
|
|
case SERVO_TEST:
|
|
case AUTO:
|
|
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED |
|
|
MAV_MODE_FLAG_STABILIZE_ENABLED;
|
|
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
|
|
// APM does in any mode, as that is defined as "system finds its own goal
|
|
// positions", which APM does not currently do
|
|
break;
|
|
|
|
case INITIALISING:
|
|
break;
|
|
}
|
|
|
|
// 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;
|
|
}
|
|
|
|
return (MAV_MODE)_base_mode;
|
|
}
|
|
|
|
uint32_t GCS_MAVLINK_Tracker::custom_mode() const
|
|
{
|
|
return tracker.control_mode;
|
|
}
|
|
|
|
MAV_STATE GCS_MAVLINK_Tracker::system_status() const
|
|
{
|
|
if (tracker.control_mode == INITIALISING) {
|
|
return MAV_STATE_CALIBRATING;
|
|
}
|
|
return MAV_STATE_ACTIVE;
|
|
}
|
|
|
|
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);
|
|
}
|
|
|
|
void Tracker::send_nav_controller_output(mavlink_channel_t chan)
|
|
{
|
|
float alt_diff = (g.alt_source == ALT_SOURCE_BARO) ? nav_status.alt_difference_baro : nav_status.alt_difference_gps;
|
|
|
|
mavlink_msg_nav_controller_output_send(
|
|
chan,
|
|
0,
|
|
nav_status.pitch,
|
|
nav_status.bearing,
|
|
nav_status.bearing,
|
|
MIN(nav_status.distance, UINT16_MAX),
|
|
alt_diff,
|
|
0,
|
|
0);
|
|
}
|
|
|
|
|
|
bool GCS_MAVLINK_Tracker::handle_guided_request(AP_Mission::Mission_Command&)
|
|
{
|
|
// do nothing
|
|
return false;
|
|
}
|
|
|
|
void GCS_MAVLINK_Tracker::handle_change_alt_request(AP_Mission::Mission_Command&)
|
|
{
|
|
// do nothing
|
|
}
|
|
|
|
// try to send a message, return false if it won't fit in the serial tx buffer
|
|
bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
|
{
|
|
switch (id) {
|
|
|
|
case MSG_NAV_CONTROLLER_OUTPUT:
|
|
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
|
|
tracker.send_nav_controller_output(chan);
|
|
break;
|
|
|
|
case MSG_EXTENDED_STATUS1:
|
|
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
|
tracker.send_extended_status1(chan);
|
|
break;
|
|
|
|
default:
|
|
return GCS_MAVLINK::try_send_message(id);
|
|
}
|
|
return true;
|
|
}
|
|
|
|
|
|
/*
|
|
default stream rates to 1Hz
|
|
*/
|
|
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
|
// @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
|
|
};
|
|
|
|
static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
|
MSG_RAW_IMU1, // RAW_IMU, SCALED_IMU2, SCALED_IMU3
|
|
MSG_RAW_IMU2, // SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3
|
|
MSG_RAW_IMU3 // SENSOR_OFFSETS
|
|
};
|
|
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
|
MSG_EXTENDED_STATUS1, // SYS_STATUS, POWER_STATUS
|
|
MSG_EXTENDED_STATUS2, // MEMINFO
|
|
MSG_NAV_CONTROLLER_OUTPUT,
|
|
MSG_GPS_RAW,
|
|
MSG_GPS_RTK,
|
|
MSG_GPS2_RAW,
|
|
MSG_GPS2_RTK,
|
|
};
|
|
static const ap_message STREAM_POSITION_msgs[] = {
|
|
MSG_LOCATION,
|
|
MSG_LOCAL_POSITION
|
|
};
|
|
static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {
|
|
MSG_SERVO_OUTPUT_RAW,
|
|
};
|
|
static const ap_message STREAM_RC_CHANNELS_msgs[] = {
|
|
MSG_RADIO_IN
|
|
};
|
|
static const ap_message STREAM_EXTRA1_msgs[] = {
|
|
MSG_ATTITUDE,
|
|
};
|
|
static const ap_message STREAM_EXTRA3_msgs[] = {
|
|
MSG_AHRS,
|
|
MSG_HWSTATUS,
|
|
MSG_SIMSTATE, // SIMSTATE, AHRS2
|
|
MSG_MAG_CAL_REPORT,
|
|
MSG_MAG_CAL_PROGRESS,
|
|
};
|
|
|
|
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),
|
|
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
|
|
};
|
|
|
|
/*
|
|
We eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and
|
|
MAVLINK_MSG_ID_SCALED_PRESSUREs
|
|
*/
|
|
void GCS_MAVLINK_Tracker::packetReceived(const mavlink_status_t &status,
|
|
mavlink_message_t &msg)
|
|
{
|
|
// return immediately if sysid doesn't match our target sysid
|
|
if ((tracker.g.sysid_target != 0) && (tracker.g.sysid_target != msg.sysid)) {
|
|
return;
|
|
}
|
|
|
|
switch (msg.msgid) {
|
|
case MAVLINK_MSG_ID_HEARTBEAT:
|
|
{
|
|
mavlink_check_target(msg);
|
|
break;
|
|
}
|
|
|
|
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
|
|
{
|
|
// decode
|
|
mavlink_global_position_int_t packet;
|
|
mavlink_msg_global_position_int_decode(&msg, &packet);
|
|
tracker.tracking_update_position(packet);
|
|
break;
|
|
}
|
|
|
|
case MAVLINK_MSG_ID_SCALED_PRESSURE:
|
|
{
|
|
// decode
|
|
mavlink_scaled_pressure_t packet;
|
|
mavlink_msg_scaled_pressure_decode(&msg, &packet);
|
|
tracker.tracking_update_pressure(packet);
|
|
break;
|
|
}
|
|
}
|
|
GCS_MAVLINK::packetReceived(status, msg);
|
|
}
|
|
|
|
// locks onto a particular target sysid and sets it's position data stream to at least 1hz
|
|
void GCS_MAVLINK_Tracker::mavlink_check_target(const mavlink_message_t &msg)
|
|
{
|
|
// exit immediately if the target has already been set
|
|
if (tracker.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 (tracker.g.sysid_target == 0) {
|
|
tracker.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
|
|
tracker.gcs().request_datastream_position(msg.sysid, msg.compid);
|
|
tracker.gcs().request_datastream_airpressure(msg.sysid, msg.compid);
|
|
|
|
// flag target has been set
|
|
tracker.target_set = true;
|
|
}
|
|
|
|
uint8_t GCS_MAVLINK_Tracker::sysid_my_gcs() const
|
|
{
|
|
return tracker.g.sysid_my_gcs;
|
|
}
|
|
|
|
MAV_RESULT GCS_MAVLINK_Tracker::_handle_command_preflight_calibration_baro()
|
|
{
|
|
MAV_RESULT ret = GCS_MAVLINK::_handle_command_preflight_calibration_baro();
|
|
if (ret == MAV_RESULT_ACCEPTED) {
|
|
// zero the altitude difference on next baro update
|
|
tracker.nav_status.need_altitude_calibration = true;
|
|
}
|
|
return ret;
|
|
}
|
|
|
|
void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
|
{
|
|
switch (msg->msgid) {
|
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT:
|
|
break;
|
|
|
|
case MAVLINK_MSG_ID_COMMAND_LONG:
|
|
{
|
|
// decode
|
|
mavlink_command_long_t packet;
|
|
mavlink_msg_command_long_decode(msg, &packet);
|
|
|
|
MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
|
|
|
|
// do command
|
|
send_text(MAV_SEVERITY_INFO,"Command received: ");
|
|
|
|
switch(packet.command) {
|
|
|
|
case MAV_CMD_COMPONENT_ARM_DISARM:
|
|
if (packet.target_component == MAV_COMP_ID_SYSTEM_CONTROL) {
|
|
if (is_equal(packet.param1,1.0f)) {
|
|
tracker.arm_servos();
|
|
result = MAV_RESULT_ACCEPTED;
|
|
} else if (is_zero(packet.param1)) {
|
|
tracker.disarm_servos();
|
|
result = MAV_RESULT_ACCEPTED;
|
|
} else {
|
|
result = MAV_RESULT_UNSUPPORTED;
|
|
}
|
|
} else {
|
|
result = MAV_RESULT_UNSUPPORTED;
|
|
}
|
|
break;
|
|
|
|
case MAV_CMD_DO_SET_SERVO:
|
|
if (tracker.servo_test_set_servo(packet.param1, packet.param2)) {
|
|
result = MAV_RESULT_ACCEPTED;
|
|
}
|
|
break;
|
|
|
|
// mavproxy/mavutil sends this when auto command is entered
|
|
case MAV_CMD_MISSION_START:
|
|
tracker.set_mode(AUTO, MODE_REASON_GCS_COMMAND);
|
|
result = MAV_RESULT_ACCEPTED;
|
|
break;
|
|
|
|
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
|
{
|
|
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
|
|
// when packet.param1 == 3 we reboot to hold in bootloader
|
|
hal.scheduler->reboot(is_equal(packet.param1,3.0f));
|
|
result = MAV_RESULT_ACCEPTED;
|
|
}
|
|
break;
|
|
}
|
|
|
|
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;
|
|
|
|
default:
|
|
result = handle_command_long_message(packet);
|
|
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;
|
|
MAV_MISSION_RESULT 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) {
|
|
tracker.set_home(tell_command); // New home in EEPROM
|
|
send_text(MAV_SEVERITY_INFO,"New HOME received");
|
|
waypoint_receiving = false;
|
|
}
|
|
|
|
mission_failed:
|
|
// we are rejecting the mission/waypoint
|
|
mavlink_msg_mission_ack_send(
|
|
chan,
|
|
msg->sysid,
|
|
msg->compid,
|
|
result,
|
|
MAV_MISSION_TYPE_MISSION);
|
|
break;
|
|
}
|
|
|
|
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
|
{
|
|
mavlink_manual_control_t packet;
|
|
mavlink_msg_manual_control_decode(msg, &packet);
|
|
tracker.tracking_manual_control(packet);
|
|
break;
|
|
}
|
|
|
|
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
|
|
{
|
|
// decode
|
|
mavlink_global_position_int_t packet;
|
|
mavlink_msg_global_position_int_decode(msg, &packet);
|
|
tracker.tracking_update_position(packet);
|
|
break;
|
|
}
|
|
|
|
case MAVLINK_MSG_ID_SCALED_PRESSURE:
|
|
{
|
|
// decode
|
|
mavlink_scaled_pressure_t packet;
|
|
mavlink_msg_scaled_pressure_decode(msg, &packet);
|
|
tracker.tracking_update_pressure(packet);
|
|
break;
|
|
}
|
|
|
|
default:
|
|
handle_common_message(msg);
|
|
break;
|
|
} // end switch
|
|
} // end handle mavlink
|
|
|
|
|
|
/*
|
|
* a delay() callback that processes MAVLink packets. We set this as the
|
|
* callback in long running library initialisation routines to allow
|
|
* MAVLink to process packets while waiting for the initialisation to
|
|
* complete
|
|
*/
|
|
void Tracker::mavlink_delay_cb()
|
|
{
|
|
static uint32_t last_1hz, last_50hz, last_5s;
|
|
if (!gcs().chan(0).initialised) {
|
|
return;
|
|
}
|
|
|
|
DataFlash.EnableWrites(false);
|
|
|
|
uint32_t tnow = AP_HAL::millis();
|
|
if (tnow - last_1hz > 1000) {
|
|
last_1hz = tnow;
|
|
gcs().send_message(MSG_HEARTBEAT);
|
|
gcs().send_message(MSG_EXTENDED_STATUS1);
|
|
}
|
|
if (tnow - last_50hz > 20) {
|
|
last_50hz = tnow;
|
|
gcs_update();
|
|
gcs_data_stream_send();
|
|
notify.update();
|
|
}
|
|
if (tnow - last_5s > 5000) {
|
|
last_5s = tnow;
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
|
}
|
|
DataFlash.EnableWrites(true);
|
|
}
|
|
|
|
/*
|
|
* send data streams in the given rate range on both links
|
|
*/
|
|
void Tracker::gcs_data_stream_send(void)
|
|
{
|
|
gcs().data_stream_send();
|
|
}
|
|
|
|
/*
|
|
* look for incoming commands on the GCS links
|
|
*/
|
|
void Tracker::gcs_update(void)
|
|
{
|
|
gcs().update();
|
|
}
|
|
|
|
/**
|
|
retry any deferred messages
|
|
*/
|
|
void Tracker::gcs_retry_deferred(void)
|
|
{
|
|
gcs().retry_deferred();
|
|
}
|
|
|
|
Compass *GCS_MAVLINK_Tracker::get_compass() const
|
|
{
|
|
return &tracker.compass;
|
|
}
|
|
|
|
/*
|
|
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, MODE_REASON_GCS_COMMAND);
|
|
return true;
|
|
}
|
|
return false;
|
|
}
|
|
|
|
const AP_FWVersion &GCS_MAVLINK_Tracker::get_fwver() const
|
|
{
|
|
return tracker.fwver;
|
|
}
|
|
|
|
/* 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) {}
|
|
void AP_Camera::send_feedback(mavlink_channel_t chan) {}
|
|
/* end dummy methods to avoid having to link against AP_Camera */
|
|
|
|
// dummy method to avoid linking AFS
|
|
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {return false;}
|