2011-09-08 22:29:39 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2013-10-04 00:33:31 -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
2014-05-15 07:53:18 -03:00
#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 | MAV_SYS_STATUS_AHRS)
2013-10-04 00:33:31 -03:00
2011-09-08 22:29:39 -03:00
// use this to prevent recursion during sensor init
static bool in_mavlink_delay;
2013-07-05 05:05:27 -03:00
// true if we are out of time in our event timeslice
static bool gcs_out_of_time;
2011-09-18 03:39:09 -03:00
// check if a message will fit in the payload space available
2012-08-21 23:19:51 -03:00
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_ ## id ## _LEN) return false
2011-09-18 03:39:09 -03:00
/*
2012-08-21 23:19:51 -03: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
2011-09-18 03:39:09 -03:00
*/
static NOINLINE void send_heartbeat(mavlink_channel_t chan)
{
2011-10-29 22:41:32 -03:00
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
2013-09-14 22:09:02 -03:00
uint8_t system_status = is_flying() ? MAV_STATE_ACTIVE : MAV_STATE_STANDBY;
2011-10-29 22:41:32 -03:00
uint32_t custom_mode = control_mode;
2013-02-08 22:11:26 -04:00
2013-07-19 01:11:16 -03:00
if (failsafe.state != FAILSAFE_NONE) {
2013-02-08 22:11:26 -04:00
system_status = MAV_STATE_CRITICAL;
}
2011-10-16 04:01:14 -03:00
2011-10-29 22:41:32 -03:00
// work out the base_mode. This value is not very useful
2011-10-16 04:01:14 -03:00
// 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:
2012-12-04 02:32:37 -04:00
case TRAINING:
2013-07-10 10:25:38 -03:00
case ACRO:
2011-10-16 04:01:14 -03:00
base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
break;
case STABILIZE:
case FLY_BY_WIRE_A:
2014-04-12 01:12:14 -03:00
case AUTOTUNE:
2011-10-16 04:01:14 -03:00
case FLY_BY_WIRE_B:
2013-07-13 07:05:53 -03:00
case CRUISE:
2011-10-16 04:01:14 -03:00
base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
break;
case AUTO:
case RTL:
case LOITER:
case GUIDED:
case CIRCLE:
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:
system_status = MAV_STATE_CALIBRATING;
break;
}
2012-12-04 02:32:37 -04:00
if (!training_manual_pitch || !training_manual_roll) {
base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
}
2011-10-16 04:01:14 -03:00
if (control_mode != MANUAL && control_mode != INITIALISING) {
// stabiliser of some form is enabled
base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
}
2013-04-01 18:52:56 -03:00
if (g.stick_mixing != STICK_MIXING_DISABLED && control_mode != INITIALISING) {
2011-10-16 04:01:14 -03:00
// all modes except INITIALISING have some form of manual
// override if stick mixing is enabled
base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
}
#if HIL_MODE != HIL_MODE_DISABLED
base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
#endif
// we are armed if we are not initialising
2014-02-18 19:53:26 -04:00
if (control_mode != INITIALISING && ahrs.get_armed()) {
2011-10-16 04:01:14 -03:00
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
}
2011-10-29 22:41:32 -03:00
// indicate we have set a custom mode
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
2011-10-16 04:01:14 -03:00
mavlink_msg_heartbeat_send(
chan,
MAV_TYPE_FIXED_WING,
MAV_AUTOPILOT_ARDUPILOTMEGA,
base_mode,
custom_mode,
system_status);
2011-09-18 03:39:09 -03:00
}
static NOINLINE void send_attitude(mavlink_channel_t chan)
{
2012-03-11 05:13:31 -03:00
Vector3f omega = ahrs.get_gyro();
2011-09-18 03:39:09 -03:00
mavlink_msg_attitude_send(
chan,
2012-07-19 22:57:15 -03:00
millis(),
2012-03-11 05:13:31 -03:00
ahrs.roll,
2012-08-07 03:05:51 -03:00
ahrs.pitch - radians(g.pitch_trim_cd*0.01),
2012-03-11 05:13:31 -03:00
ahrs.yaw,
2011-09-18 03:39:09 -03:00
omega.x,
omega.y,
omega.z);
}
2011-12-15 21:41:11 -04:00
#if GEOFENCE_ENABLED == ENABLED
static NOINLINE void send_fence_status(mavlink_channel_t chan)
{
geofence_send_status(chan);
}
#endif
2013-12-14 22:07:48 -04:00
static NOINLINE void send_extended_status1(mavlink_channel_t chan)
2011-09-18 03:39:09 -03:00
{
2013-10-04 00:33:31 -03:00
uint32_t control_sensors_present;
2011-10-16 04:01:14 -03:00
uint32_t control_sensors_enabled;
uint32_t control_sensors_health;
2013-10-04 00:33:31 -03:00
// default sensors present
control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT;
2011-10-16 04:01:14 -03:00
// first what sensors/controllers we have
if (g.compass_enabled) {
2013-10-04 00:33:31 -03:00
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG; // compass present
}
2013-10-29 19:03:20 -03:00
if (airspeed.enabled()) {
2013-10-04 00:33:31 -03:00
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
2011-10-16 04:01:14 -03:00
}
2014-03-28 16:52:48 -03:00
if (gps.status() > AP_GPS::NO_GPS) {
2013-10-04 00:33:31 -03:00
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
2011-10-16 04:01:14 -03:00
}
2014-02-13 18:49:42 -04:00
if (geofence_present()) {
control_sensors_present |= MAV_SYS_STATUS_GEOFENCE;
}
2011-10-16 04:01:14 -03:00
2014-02-13 18:49:42 -04:00
// all present sensors enabled by default except rate control, attitude stabilization, yaw, altitude, position control, geofence and motor output which we will set individually
control_sensors_enabled = control_sensors_present & (~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_GEOFENCE);
2011-10-16 04:01:14 -03:00
2013-10-29 19:03:20 -03:00
if (airspeed.enabled() && airspeed.use()) {
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
}
2014-02-13 18:49:42 -04:00
if (geofence_enabled()) {
control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE;
}
2011-10-16 04:01:14 -03:00
switch (control_mode) {
case MANUAL:
break;
2013-07-10 10:25:38 -03:00
case ACRO:
2013-10-04 00:33:31 -03:00
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control
2013-07-10 10:25:38 -03:00
break;
2011-10-16 04:01:14 -03:00
case STABILIZE:
case FLY_BY_WIRE_A:
2014-04-12 01:12:14 -03:00
case AUTOTUNE:
2013-10-04 00:33:31 -03:00
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation
2011-10-16 04:01:14 -03:00
break;
case FLY_BY_WIRE_B:
2013-07-13 07:05:53 -03:00
case CRUISE:
2013-10-04 00:33:31 -03:00
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; // motor control
2011-10-16 04:01:14 -03:00
break;
2012-12-04 02:32:37 -04:00
case TRAINING:
if (!training_manual_roll || !training_manual_pitch) {
2013-10-04 00:33:31 -03:00
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation
2012-12-04 02:32:37 -04:00
}
break;
2011-10-16 04:01:14 -03:00
case AUTO:
case RTL:
case LOITER:
case GUIDED:
case CIRCLE:
2013-10-04 00:33:31 -03:00
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL; // 3D angular rate control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_YAW_POSITION; // yaw position
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; // altitude control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; // motor control
2011-10-16 04:01:14 -03:00
break;
case INITIALISING:
break;
}
2014-02-13 18:49:42 -04:00
// default: all present sensors healthy except 3D_MAG, GPS, DIFFERNTIAL_PRESSURE. GEOFENCE always defaults to healthy.
2013-10-29 19:03:20 -03:00
control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_3D_MAG |
MAV_SYS_STATUS_SENSOR_GPS |
MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE);
2014-02-13 18:49:42 -04:00
control_sensors_health |= MAV_SYS_STATUS_GEOFENCE;
2014-05-15 07:53:18 -03:00
if (!ahrs.healthy()) {
// AHRS subsystem is unhealthy
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}
2014-03-23 17:03:53 -03:00
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
2013-10-04 00:33:31 -03:00
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
2012-11-11 20:26:54 -04:00
}
2014-03-28 16:52:48 -03:00
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
2013-10-04 00:33:31 -03:00
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
2012-11-11 20:26:54 -04:00
}
2013-10-29 19:03:20 -03:00
if (!ins.healthy()) {
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
}
if (airspeed.healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
}
2014-02-13 18:49:42 -04:00
if (geofence_breached()) {
control_sensors_health &= ~MAV_SYS_STATUS_GEOFENCE;
}
2012-11-11 20:26:54 -04:00
2013-10-01 10:31:00 -03:00
int16_t battery_current = -1;
int8_t battery_remaining = -1;
2011-10-16 04:01:14 -03:00
2013-09-29 09:54:39 -03:00
if (battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) {
battery_remaining = battery.capacity_remaining_pct();
battery_current = battery.current_amps() * 100;
2011-10-16 04:01:14 -03:00
}
mavlink_msg_sys_status_send(
chan,
control_sensors_present,
control_sensors_enabled,
control_sensors_health,
2013-07-23 04:04:44 -03:00
(uint16_t)(scheduler.load_average(20000) * 1000),
2013-09-29 09:54:39 -03:00
battery.voltage() * 1000, // mV
2011-10-16 04:01:14 -03:00
battery_current, // in 10mA units
battery_remaining, // in %
0, // comm drops %,
0, // comm drops in pkts,
0, 0, 0, 0);
2011-09-18 03:39:09 -03:00
}
static void NOINLINE send_location(mavlink_channel_t chan)
{
2014-03-28 16:52:48 -03:00
uint32_t fix_time_ms;
2012-11-13 01:38:24 -04:00
// if we have a GPS fix, take the time as the last fix time. That
// allows us to correctly calculate velocities and extrapolate
// positions.
// If we don't have a GPS fix then we are dead reckoning, and will
// use the current boot time as the fix time.
2014-03-28 16:52:48 -03:00
if (gps.status() >= AP_GPS::GPS_OK_FIX_2D) {
fix_time_ms = gps.last_fix_time_ms();
2012-11-13 01:38:24 -04:00
} else {
2014-03-28 16:52:48 -03:00
fix_time_ms = hal.scheduler->millis();
2012-11-13 01:38:24 -04:00
}
2014-03-28 16:52:48 -03:00
const Vector3f &vel = gps.velocity();
2011-10-16 04:01:14 -03:00
mavlink_msg_global_position_int_send(
chan,
2014-03-28 16:52:48 -03:00
fix_time_ms,
2011-10-16 04:01:14 -03:00
current_loc.lat, // in 1E7 degrees
current_loc.lng, // in 1E7 degrees
2014-03-28 16:52:48 -03:00
gps.location().alt * 10UL, // millimeters above sea level
2013-07-10 00:40:13 -03:00
relative_altitude() * 1.0e3, // millimeters above ground
2014-03-28 16:52:48 -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)
2012-08-10 23:01:08 -03:00
ahrs.yaw_sensor);
2011-09-18 03:39:09 -03:00
}
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
{
mavlink_msg_nav_controller_output_send(
chan,
2012-08-07 03:05:51 -03:00
nav_roll_cd * 0.01,
nav_pitch_cd * 0.01,
2013-04-11 21:25:46 -03:00
nav_controller->nav_bearing_cd() * 0.01f,
nav_controller->target_bearing_cd() * 0.01f,
2011-09-18 03:39:09 -03:00
wp_distance,
2012-08-07 03:05:51 -03:00
altitude_error_cm * 0.01,
airspeed_error_cm,
2013-04-11 21:25:46 -03:00
nav_controller->crosstrack_error());
2011-09-18 03:39:09 -03:00
}
2013-10-23 08:15:06 -03:00
2013-09-20 20:27:22 -03:00
#if HIL_MODE != HIL_MODE_DISABLED
2013-12-16 20:15:28 -04:00
void NOINLINE send_servo_out(mavlink_channel_t chan)
2011-09-18 03:39:09 -03:00
{
// normalized values scaled to -10000 to 10000
2011-10-16 04:01:14 -03:00
// This is used for HIL. Do not change without discussing with
// HIL maintainers
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
2014-03-16 03:07:07 -03:00
10000 * channel_roll->norm_output() * (channel_roll->get_reverse()?-1:1),
10000 * channel_pitch->norm_output() * (channel_pitch->get_reverse()?-1:1),
10000 * channel_throttle->norm_output() * (channel_throttle->get_reverse()?-1:1),
10000 * channel_rudder->norm_output() * (channel_rudder->get_reverse()?-1:1),
2011-10-16 04:01:14 -03:00
0,
0,
0,
0,
2012-08-22 00:58:25 -03:00
receiver_rssi);
2011-09-18 03:39:09 -03:00
}
2013-09-20 20:27:22 -03:00
#endif
2011-09-18 03:39:09 -03:00
static void NOINLINE send_radio_out(mavlink_channel_t chan)
{
2013-03-30 00:38:43 -03:00
#if HIL_MODE != HIL_MODE_DISABLED
if (!g.hil_servos) {
mavlink_msg_servo_output_raw_send(
chan,
micros(),
0, // port
2013-06-03 02:11:55 -03:00
RC_Channel::rc_channel(0)->radio_out,
RC_Channel::rc_channel(1)->radio_out,
RC_Channel::rc_channel(2)->radio_out,
RC_Channel::rc_channel(3)->radio_out,
RC_Channel::rc_channel(4)->radio_out,
RC_Channel::rc_channel(5)->radio_out,
RC_Channel::rc_channel(6)->radio_out,
RC_Channel::rc_channel(7)->radio_out);
2013-03-30 00:38:43 -03:00
return;
}
#endif
2012-08-21 23:19:51 -03:00
mavlink_msg_servo_output_raw_send(
chan,
micros(),
0, // port
2012-12-04 18:22:21 -04:00
hal.rcout->read(0),
hal.rcout->read(1),
hal.rcout->read(2),
hal.rcout->read(3),
hal.rcout->read(4),
hal.rcout->read(5),
hal.rcout->read(6),
hal.rcout->read(7));
2011-09-18 03:39:09 -03:00
}
static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
{
2012-08-24 09:03:40 -03:00
float aspeed;
2012-09-19 19:00:54 -03:00
if (airspeed.enabled()) {
2012-08-24 09:03:40 -03:00
aspeed = airspeed.get_airspeed();
} else if (!ahrs.airspeed_estimate(&aspeed)) {
aspeed = 0;
}
2013-06-03 02:32:08 -03:00
float throttle_norm = channel_throttle->norm_output() * 100;
2012-12-18 22:36:00 -04:00
throttle_norm = constrain_int16(throttle_norm, -100, 100);
2012-11-19 22:50:11 -04:00
uint16_t throttle = ((uint16_t)(throttle_norm + 100)) / 2;
2011-09-18 03:39:09 -03:00
mavlink_msg_vfr_hud_send(
chan,
2012-08-24 09:03:40 -03:00
aspeed,
2014-03-28 16:52:48 -03:00
gps.ground_speed(),
2012-03-11 05:13:31 -03:00
(ahrs.yaw_sensor / 100) % 360,
2012-11-19 22:50:11 -04:00
throttle,
2011-09-18 03:39:09 -03:00
current_loc.alt / 100.0,
2012-07-04 22:11:07 -03:00
barometer.get_climb_rate());
2011-09-18 03:39:09 -03:00
}
static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
{
2013-12-08 23:10:35 -04:00
const Vector3f &accel = ins.get_accel();
const Vector3f &gyro = ins.get_gyro();
const Vector3f &mag = compass.get_field();
2011-09-18 03:39:09 -03:00
mavlink_msg_raw_imu_send(
chan,
micros(),
2013-01-01 22:52:35 -04:00
accel.x * 1000.0 / GRAVITY_MSS,
accel.y * 1000.0 / GRAVITY_MSS,
accel.z * 1000.0 / GRAVITY_MSS,
2011-09-18 03:39:09 -03:00
gyro.x * 1000.0,
gyro.y * 1000.0,
gyro.z * 1000.0,
2013-12-08 23:10:35 -04:00
mag.x,
mag.y,
mag.z);
2013-12-09 02:14:59 -04:00
if (ins.get_gyro_count() <= 1 &&
ins.get_accel_count() <= 1 &&
compass.get_count() <= 1) {
return;
}
const Vector3f &accel2 = ins.get_accel(1);
const Vector3f &gyro2 = ins.get_gyro(1);
const Vector3f &mag2 = compass.get_field(1);
mavlink_msg_scaled_imu2_send(
chan,
millis(),
accel2.x * 1000.0f / GRAVITY_MSS,
accel2.y * 1000.0f / GRAVITY_MSS,
accel2.z * 1000.0f / GRAVITY_MSS,
gyro2.x * 1000.0f,
gyro2.y * 1000.0f,
gyro2.z * 1000.0f,
mag2.x,
mag2.y,
mag2.z);
2011-09-18 03:39:09 -03:00
}
static void NOINLINE send_raw_imu2(mavlink_channel_t chan)
{
2013-09-21 08:31:03 -03:00
float pressure = barometer.get_pressure();
2011-09-18 03:39:09 -03:00
mavlink_msg_scaled_pressure_send(
chan,
2012-07-19 22:57:15 -03:00
millis(),
2013-09-21 08:31:03 -03:00
pressure*0.01f, // hectopascal
(pressure - barometer.get_ground_pressure())*0.01f, // hectopascal
barometer.get_temperature()*100); // 0.01 degrees C
2011-09-18 03:39:09 -03:00
}
static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
{
2013-09-20 20:35:45 -03:00
// run this message at a much lower rate - otherwise it
// pointlessly wastes quite a lot of bandwidth
static uint8_t counter;
if (counter++ < 10) {
return;
}
counter = 0;
2011-09-18 03:39:09 -03:00
Vector3f mag_offsets = compass.get_offsets();
2012-11-20 03:23:31 -04:00
Vector3f accel_offsets = ins.get_accel_offsets();
Vector3f gyro_offsets = ins.get_gyro_offsets();
2011-09-18 03:39:09 -03:00
mavlink_msg_sensor_offsets_send(chan,
mag_offsets.x,
mag_offsets.y,
mag_offsets.z,
compass.get_declination(),
2013-09-21 08:31:03 -03:00
barometer.get_pressure(),
barometer.get_temperature()*100,
2012-11-20 03:23:31 -04:00
gyro_offsets.x,
gyro_offsets.y,
gyro_offsets.z,
accel_offsets.x,
accel_offsets.y,
accel_offsets.z);
2011-09-18 03:39:09 -03:00
}
2012-03-01 00:23:00 -04:00
2012-03-11 05:13:31 -03:00
static void NOINLINE send_ahrs(mavlink_channel_t chan)
2012-03-01 00:23:00 -04:00
{
2013-12-08 23:10:35 -04:00
const Vector3f &omega_I = ahrs.get_gyro_drift();
2012-03-11 05:13:31 -03:00
mavlink_msg_ahrs_send(
2012-03-01 00:23:00 -04:00
chan,
omega_I.x,
omega_I.y,
omega_I.z,
2012-03-11 05:13:31 -03:00
0,
0,
ahrs.get_error_rp(),
ahrs.get_error_yaw());
2012-03-01 00:23:00 -04:00
}
2013-11-22 19:47:34 -04:00
#if HIL_MODE != HIL_MODE_DISABLED
/*
keep last HIL_STATE message to allow sending SIM_STATE
*/
static mavlink_hil_state_t last_hil_state;
#endif
2012-03-01 00:23:00 -04:00
// report simulator state
static void NOINLINE send_simstate(mavlink_channel_t chan)
{
2012-12-20 07:46:48 -04:00
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
2012-06-29 02:10:35 -03:00
sitl.simstate_send(chan);
2013-11-22 19:47:34 -04:00
#elif HIL_MODE != HIL_MODE_DISABLED
mavlink_msg_simstate_send(chan,
last_hil_state.roll,
last_hil_state.pitch,
last_hil_state.yaw,
last_hil_state.xacc*0.001*GRAVITY_MSS,
last_hil_state.yacc*0.001*GRAVITY_MSS,
last_hil_state.zacc*0.001*GRAVITY_MSS,
last_hil_state.rollspeed,
last_hil_state.pitchspeed,
last_hil_state.yawspeed,
last_hil_state.lat,
last_hil_state.lon);
2012-03-01 00:23:00 -04:00
#endif
2012-12-20 07:46:48 -04:00
}
2012-03-01 00:23:00 -04:00
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
{
mavlink_msg_hwstatus_send(
chan,
2014-02-13 02:08:09 -04:00
hal.analogin->board_voltage()*1000,
2012-12-04 18:22:21 -04:00
hal.i2c->lockup_count());
2012-07-06 06:22:19 -03:00
}
2012-03-01 00:23:00 -04:00
2012-08-11 02:57:13 -03:00
static void NOINLINE send_wind(mavlink_channel_t chan)
{
Vector3f wind = ahrs.wind_estimate();
mavlink_msg_wind_send(
chan,
2013-01-10 14:42:24 -04:00
degrees(atan2f(-wind.y, -wind.x)), // use negative, to give
2012-11-18 16:10:26 -04:00
// direction wind is coming from
2012-12-18 22:36:00 -04:00
wind.length(),
2012-08-11 02:57:13 -03:00
wind.z);
}
2013-10-30 19:54:45 -03:00
static void NOINLINE send_rangefinder(mavlink_channel_t chan)
{
if (!sonar.enabled()) {
// no sonar to report
return;
}
mavlink_msg_rangefinder_send(
chan,
sonar.distance_cm() * 0.01f,
sonar.voltage());
}
2011-09-18 03:39:09 -03:00
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
{
2014-04-21 22:38:03 -03:00
mavlink_msg_mission_current_send(chan, mission.get_current_nav_index());
2011-09-18 03:39:09 -03:00
}
2011-09-18 05:57:41 -03:00
static void NOINLINE send_statustext(mavlink_channel_t chan)
{
2013-11-22 04:18:19 -04:00
mavlink_statustext_t *s = &gcs[chan-MAVLINK_COMM_0].pending_status;
2011-09-18 05:57:41 -03:00
mavlink_msg_statustext_send(
chan,
2012-09-24 04:39:09 -03:00
s->severity,
s->text);
2011-09-18 05:57:41 -03:00
}
2012-08-29 19:59:39 -03:00
// are we still delaying telemetry to try to avoid Xbee bricking?
static bool telemetry_delayed(mavlink_channel_t chan)
{
uint32_t tnow = millis() >> 10;
2013-01-01 19:18:45 -04:00
if (tnow > (uint32_t)g.telem_delay) {
2012-08-29 19:59:39 -03:00
return false;
}
2013-09-19 03:23:58 -03:00
if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
// this is USB telemetry, so won't be an Xbee
2012-08-29 19:59:39 -03:00
return false;
}
// we're either on the 2nd UART, or no USB cable is connected
2013-09-19 03:23:58 -03:00
// we need to delay telemetry by the TELEM_DELAY time
2012-08-29 19:59:39 -03:00
return true;
}
2011-09-18 03:39:09 -03:00
// try to send a message, return false if it won't fit in the serial tx buffer
2014-03-18 20:56:25 -03:00
bool GCS_MAVLINK::try_send_message(enum ap_message id)
2011-09-18 03:39:09 -03:00
{
2012-08-18 06:26:13 -03:00
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
2011-09-18 03:39:09 -03:00
2012-08-29 19:59:39 -03:00
if (telemetry_delayed(chan)) {
2011-09-18 03:39:09 -03:00
return false;
}
2013-07-05 05:05:27 -03:00
// if we don't have at least 1ms 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
2013-07-14 04:28:34 -03:00
if (!in_mavlink_delay && scheduler.time_available_usec() < 1200) {
2013-07-05 05:05:27 -03:00
gcs_out_of_time = true;
return false;
}
2011-09-18 03:39:09 -03:00
switch (id) {
case MSG_HEARTBEAT:
CHECK_PAYLOAD_SIZE(HEARTBEAT);
2013-12-15 03:59:23 -04:00
gcs[chan-MAVLINK_COMM_0].last_heartbeat_time = hal.scheduler->millis();
2011-09-18 03:39:09 -03:00
send_heartbeat(chan);
return true;
case MSG_EXTENDED_STATUS1:
CHECK_PAYLOAD_SIZE(SYS_STATUS);
2013-12-14 22:07:48 -04:00
send_extended_status1(chan);
2014-02-13 07:08:25 -04:00
CHECK_PAYLOAD_SIZE(POWER_STATUS);
gcs[chan-MAVLINK_COMM_0].send_power_status();
2011-09-18 03:39:09 -03:00
break;
case MSG_EXTENDED_STATUS2:
CHECK_PAYLOAD_SIZE(MEMINFO);
2013-12-28 01:02:06 -04:00
gcs[chan-MAVLINK_COMM_0].send_meminfo();
2011-09-18 03:39:09 -03:00
break;
case MSG_ATTITUDE:
CHECK_PAYLOAD_SIZE(ATTITUDE);
send_attitude(chan);
break;
case MSG_LOCATION:
CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);
send_location(chan);
break;
case MSG_NAV_CONTROLLER_OUTPUT:
if (control_mode != MANUAL) {
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
send_nav_controller_output(chan);
}
break;
case MSG_GPS_RAW:
2011-10-16 04:01:14 -03:00
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
2014-05-27 20:36:04 -03:00
gcs[chan-MAVLINK_COMM_0].send_gps_raw(gps);
2011-09-18 03:39:09 -03:00
break;
2013-10-23 08:15:06 -03:00
case MSG_SYSTEM_TIME:
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
2014-05-27 20:36:04 -03:00
gcs[chan-MAVLINK_COMM_0].send_system_time(gps);
2013-10-23 08:15:06 -03:00
break;
2011-09-18 03:39:09 -03:00
case MSG_SERVO_OUT:
2013-09-20 20:27:22 -03:00
#if HIL_MODE != HIL_MODE_DISABLED
2011-09-18 03:39:09 -03:00
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
send_servo_out(chan);
2013-09-20 20:27:22 -03:00
#endif
2011-09-18 03:39:09 -03:00
break;
case MSG_RADIO_IN:
CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
2014-05-27 20:36:04 -03:00
gcs[chan-MAVLINK_COMM_0].send_radio_in(receiver_rssi);
2011-09-18 03:39:09 -03:00
break;
case MSG_RADIO_OUT:
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
send_radio_out(chan);
break;
case MSG_VFR_HUD:
CHECK_PAYLOAD_SIZE(VFR_HUD);
send_vfr_hud(chan);
break;
case MSG_RAW_IMU1:
CHECK_PAYLOAD_SIZE(RAW_IMU);
send_raw_imu1(chan);
break;
case MSG_RAW_IMU2:
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
send_raw_imu2(chan);
break;
case MSG_RAW_IMU3:
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
send_raw_imu3(chan);
break;
case MSG_CURRENT_WAYPOINT:
2012-08-08 23:22:46 -03:00
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
2011-09-18 03:39:09 -03:00
send_current_waypoint(chan);
break;
case MSG_NEXT_PARAM:
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
2013-11-22 04:18:19 -04:00
gcs[chan-MAVLINK_COMM_0].queued_param_send();
2011-09-18 03:39:09 -03:00
break;
case MSG_NEXT_WAYPOINT:
2012-08-08 23:22:46 -03:00
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
2013-11-22 04:18:19 -04:00
gcs[chan-MAVLINK_COMM_0].queued_waypoint_send();
2011-09-18 03:39:09 -03:00
break;
2011-09-18 05:57:41 -03:00
case MSG_STATUSTEXT:
CHECK_PAYLOAD_SIZE(STATUSTEXT);
send_statustext(chan);
break;
2011-12-15 21:41:11 -04:00
#if GEOFENCE_ENABLED == ENABLED
case MSG_FENCE_STATUS:
CHECK_PAYLOAD_SIZE(FENCE_STATUS);
send_fence_status(chan);
break;
#endif
2012-03-11 05:13:31 -03:00
case MSG_AHRS:
CHECK_PAYLOAD_SIZE(AHRS);
send_ahrs(chan);
2012-03-01 00:23:00 -04:00
break;
case MSG_SIMSTATE:
2012-03-11 05:13:31 -03:00
CHECK_PAYLOAD_SIZE(SIMSTATE);
2012-03-01 00:23:00 -04:00
send_simstate(chan);
2014-01-01 22:47:23 -04:00
CHECK_PAYLOAD_SIZE(AHRS2);
2014-01-03 20:30:42 -04:00
gcs[chan-MAVLINK_COMM_0].send_ahrs2(ahrs);
2012-03-01 00:23:00 -04:00
break;
case MSG_HWSTATUS:
CHECK_PAYLOAD_SIZE(HWSTATUS);
send_hwstatus(chan);
break;
2013-10-30 19:54:45 -03:00
case MSG_RANGEFINDER:
CHECK_PAYLOAD_SIZE(RANGEFINDER);
send_rangefinder(chan);
break;
2012-08-11 02:57:13 -03:00
case MSG_WIND:
CHECK_PAYLOAD_SIZE(WIND);
send_wind(chan);
break;
2011-09-18 03:39:09 -03:00
case MSG_RETRY_DEFERRED:
break; // just here to prevent a warning
2013-12-15 03:59:23 -04:00
case MSG_LIMITS_STATUS:
// unused
break;
2012-08-21 23:19:51 -03:00
}
2011-09-18 03:39:09 -03:00
return true;
}
2013-02-19 19:08:49 -04:00
/*
default stream rates to 1Hz
*/
2012-02-12 04:20:56 -04:00
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
2013-04-03 10:58:25 -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
2013-02-19 19:08:49 -04:00
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRates[0], 1),
2013-04-03 10:58:25 -03:00
// @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
2013-02-19 19:08:49 -04:00
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRates[1], 1),
2013-04-03 10:58:25 -03:00
// @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
2013-02-19 19:08:49 -04:00
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRates[2], 1),
2013-04-03 10:58:25 -03:00
// @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
2013-02-19 19:08:49 -04:00
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK, streamRates[3], 1),
2013-04-03 10:58:25 -03:00
// @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
2013-02-19 19:08:49 -04:00
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRates[4], 1),
2013-04-03 10:58:25 -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
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-02-19 19:08:49 -04:00
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRates[5], 1),
2013-04-03 10:58:25 -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
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-02-19 19:08:49 -04:00
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRates[6], 1),
2013-04-03 10:58:25 -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
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-02-19 19:08:49 -04:00
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRates[7], 1),
2013-04-03 10:58:25 -03:00
// @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
2013-08-11 03:00:29 -03:00
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 10),
2012-02-12 04:20:56 -04:00
AP_GROUPEND
};
2011-09-08 22:29:39 -03:00
2012-04-01 20:24:05 -03:00
// see if we should send a stream now. Called at 50Hz
bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
{
2013-02-04 17:20:15 -04:00
if (stream_num >= NUM_STREAMS) {
return false;
2013-02-03 02:43:05 -04:00
}
2013-02-04 17:20:15 -04:00
float rate = (uint8_t)streamRates[stream_num].get();
2012-04-01 20:24:05 -03:00
2012-08-15 21:50:12 -03:00
// send at a much lower rate while handling waypoints and
// parameter sends
2013-10-27 20:34:09 -03:00
if ((stream_num != STREAM_PARAMS) &&
(waypoint_receiving || _queued_parameter != NULL)) {
2012-08-15 21:50:12 -03:00
rate *= 0.25;
}
if (rate <= 0) {
2012-04-01 20:24:05 -03:00
return false;
}
if (stream_ticks[stream_num] == 0) {
// we're triggering now, setup the next trigger point
if (rate > 50) {
rate = 50;
}
2012-04-01 21:58:44 -03:00
stream_ticks[stream_num] = (50 / rate) + stream_slowdown;
2012-04-01 20:24:05 -03:00
return true;
}
// count down at 50Hz
stream_ticks[stream_num]--;
return false;
}
2011-09-08 22:29:39 -03:00
void
2012-04-01 20:24:05 -03:00
GCS_MAVLINK::data_stream_send(void)
2011-09-08 22:29:39 -03:00
{
2013-07-05 05:05:27 -03:00
gcs_out_of_time = false;
2013-12-15 03:59:23 -04:00
if (!in_mavlink_delay) {
handle_log_send(DataFlash);
}
2012-04-01 21:58:44 -03:00
if (_queued_parameter != NULL) {
2013-02-04 17:20:15 -04:00
if (streamRates[STREAM_PARAMS].get() <= 0) {
2013-08-11 03:00:29 -03:00
streamRates[STREAM_PARAMS].set(10);
2012-04-01 21:58:44 -03:00
}
if (stream_trigger(STREAM_PARAMS)) {
send_message(MSG_NEXT_PARAM);
}
2012-04-01 20:24:05 -03:00
}
2011-09-08 22:29:39 -03:00
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-05-22 03:13:23 -03:00
if (in_mavlink_delay) {
2012-12-03 08:26:39 -04:00
#if HIL_MODE != HIL_MODE_DISABLED
// in HIL we need to keep sending servo values to ensure
// the simulator doesn't pause, otherwise our sensor
// calibration could stall
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
send_message(MSG_SERVO_OUT);
}
if (stream_trigger(STREAM_RC_CHANNELS)) {
send_message(MSG_RADIO_OUT);
}
#endif
2012-05-22 03:13:23 -03:00
// don't send any other stream types while in the delay callback
return;
}
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-04-01 20:24:05 -03:00
if (stream_trigger(STREAM_RAW_SENSORS)) {
send_message(MSG_RAW_IMU1);
send_message(MSG_RAW_IMU2);
send_message(MSG_RAW_IMU3);
}
2011-09-08 22:29:39 -03:00
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-04-01 20:24:05 -03:00
if (stream_trigger(STREAM_EXTENDED_STATUS)) {
send_message(MSG_EXTENDED_STATUS1);
send_message(MSG_EXTENDED_STATUS2);
send_message(MSG_CURRENT_WAYPOINT);
2013-10-23 08:15:06 -03:00
send_message(MSG_GPS_RAW);
2012-04-01 20:24:05 -03:00
send_message(MSG_NAV_CONTROLLER_OUTPUT);
send_message(MSG_FENCE_STATUS);
}
2011-09-08 22:29:39 -03:00
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-04-01 20:24:05 -03:00
if (stream_trigger(STREAM_POSITION)) {
// sent with GPS read
send_message(MSG_LOCATION);
}
2011-09-08 22:29:39 -03:00
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-04-01 20:24:05 -03:00
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
send_message(MSG_SERVO_OUT);
}
2011-09-08 22:29:39 -03:00
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-04-01 20:24:05 -03:00
if (stream_trigger(STREAM_RC_CHANNELS)) {
send_message(MSG_RADIO_OUT);
send_message(MSG_RADIO_IN);
}
2011-09-08 22:29:39 -03:00
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-04-01 20:24:05 -03:00
if (stream_trigger(STREAM_EXTRA1)) {
send_message(MSG_ATTITUDE);
send_message(MSG_SIMSTATE);
}
2011-09-08 22:29:39 -03:00
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-04-01 20:24:05 -03:00
if (stream_trigger(STREAM_EXTRA2)) {
send_message(MSG_VFR_HUD);
}
2011-09-08 22:29:39 -03:00
2013-07-05 05:05:27 -03:00
if (gcs_out_of_time) return;
2012-04-01 20:24:05 -03:00
if (stream_trigger(STREAM_EXTRA3)) {
send_message(MSG_AHRS);
send_message(MSG_HWSTATUS);
2012-08-11 02:57:13 -03:00
send_message(MSG_WIND);
2013-10-30 19:54:45 -03:00
send_message(MSG_RANGEFINDER);
2013-10-23 08:15:06 -03:00
send_message(MSG_SYSTEM_TIME);
2012-04-01 20:24:05 -03:00
}
2011-09-08 22:29:39 -03:00
}
2011-09-18 03:39:09 -03:00
2014-03-18 19:59:51 -03:00
/*
handle a request to switch to guided mode. This happens via a
callback from handle_mission_item()
*/
void GCS_MAVLINK::handle_guided_request(AP_Mission::Mission_Command &cmd)
2011-09-08 22:29:39 -03:00
{
2014-03-18 19:59:51 -03:00
guided_WP_loc = cmd.content.location;
// add home alt if needed
if (guided_WP_loc.flags.relative_alt) {
guided_WP_loc.alt += home.alt;
}
2011-09-08 22:29:39 -03:00
2014-03-18 19:59:51 -03:00
set_mode(GUIDED);
// make any new wp uploaded instant (in case we are already in Guided mode)
set_guided_WP();
}
/*
handle a request to change current WP altitude. This happens via a
callback from handle_mission_item()
*/
void GCS_MAVLINK::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
{
if (cmd.content.location.flags.relative_alt) {
cmd.content.location.alt += home.alt;
}
next_WP_loc.alt = cmd.content.location.alt;
}
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
{
2011-09-08 22:29:39 -03:00
switch (msg->msgid) {
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
2012-08-21 23:19:51 -03:00
{
2014-03-18 18:34:35 -03:00
handle_request_data_stream(msg, true);
2012-08-21 23:19:51 -03:00
break;
}
case MAVLINK_MSG_ID_COMMAND_LONG:
{
// decode
mavlink_command_long_t packet;
mavlink_msg_command_long_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component)) break;
2011-10-16 04:01:14 -03:00
2012-09-09 22:42:30 -03:00
uint8_t result = MAV_RESULT_UNSUPPORTED;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// do command
2012-12-12 17:59:31 -04:00
send_text_P(SEVERITY_LOW,PSTR("command received: "));
2012-08-21 23:19:51 -03:00
switch(packet.command) {
case MAV_CMD_NAV_LOITER_UNLIM:
set_mode(LOITER);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
set_mode(RTL);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_MISSION_START:
set_mode(AUTO);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 ||
packet.param2 == 1) {
2013-05-02 00:38:28 -03:00
startup_INS_ground(true);
2012-08-21 23:19:51 -03:00
} else if (packet.param3 == 1) {
init_barometer();
if (airspeed.enabled()) {
zero_airspeed();
}
2011-10-29 22:41:32 -03:00
}
2012-08-21 23:19:51 -03:00
if (packet.param4 == 1) {
trim_radio();
2011-10-16 04:01:14 -03:00
}
2013-05-08 08:44:34 -03:00
#if !defined( __AVR_ATmega1280__ )
2013-05-08 03:25:35 -03:00
if (packet.param5 == 1) {
float trim_roll, trim_pitch;
AP_InertialSensor_UserInteract_MAVLink interact(chan);
2013-09-19 05:33:42 -03:00
if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) {
2013-05-08 03:25:35 -03:00
// reset ahrs's trim to suggested values from calibration routine
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
}
2013-05-08 08:44:34 -03:00
#endif
2012-08-21 23:19:51 -03:00
result = MAV_RESULT_ACCEPTED;
break;
2011-10-16 04:01:14 -03:00
2013-11-27 22:19:34 -04:00
case MAV_CMD_COMPONENT_ARM_DISARM:
2014-03-19 19:06:48 -03:00
if (packet.param1 == 1.0f) {
// run pre_arm_checks and arm_checks and display failures
if (arming.arm(AP_Arming::MAVLINK)) {
//only log if arming was successful
channel_throttle->enable_out();
Log_Arm_Disarm();
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
} else if (packet.param1 == 0.0f) {
if (arming.disarm()) {
if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) {
channel_throttle->disable_out();
2013-11-27 22:19:34 -04:00
}
2014-03-19 19:06:48 -03:00
// reset the mission on disarm
mission.stop();
//only log if disarming was successful
Log_Arm_Disarm();
result = MAV_RESULT_ACCEPTED;
2013-11-27 22:19:34 -04:00
} else {
2014-03-19 19:06:48 -03:00
result = MAV_RESULT_FAILED;
2013-11-27 22:19:34 -04:00
}
} else {
result = MAV_RESULT_UNSUPPORTED;
}
break;
2012-08-24 02:18:22 -03:00
case MAV_CMD_DO_SET_MODE:
switch ((uint16_t)packet.param1) {
case MAV_MODE_MANUAL_ARMED:
case MAV_MODE_MANUAL_DISARMED:
set_mode(MANUAL);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_MODE_AUTO_ARMED:
case MAV_MODE_AUTO_DISARMED:
set_mode(AUTO);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_MODE_STABILIZE_DISARMED:
case MAV_MODE_STABILIZE_ARMED:
set_mode(FLY_BY_WIRE_A);
result = MAV_RESULT_ACCEPTED;
break;
default:
result = MAV_RESULT_UNSUPPORTED;
}
break;
2012-09-03 07:56:36 -03:00
case MAV_CMD_DO_SET_SERVO:
2014-01-20 00:36:31 -04:00
if (ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) {
result = MAV_RESULT_ACCEPTED;
}
2012-09-03 07:56:36 -03:00
break;
2012-08-21 23:19:51 -03:00
2012-09-16 20:24:00 -03:00
case MAV_CMD_DO_REPEAT_SERVO:
2014-01-20 00:36:31 -04:00
if (ServoRelayEvents.do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4*1000)) {
result = MAV_RESULT_ACCEPTED;
}
2014-01-19 22:37:33 -04:00
break;
case MAV_CMD_DO_SET_RELAY:
2014-01-20 00:36:31 -04:00
if (ServoRelayEvents.do_set_relay(packet.param1, packet.param2)) {
result = MAV_RESULT_ACCEPTED;
}
2014-01-19 22:37:33 -04:00
break;
case MAV_CMD_DO_REPEAT_RELAY:
2014-01-20 00:36:31 -04:00
if (ServoRelayEvents.do_repeat_relay(packet.param1, packet.param2, packet.param3*1000)) {
result = MAV_RESULT_ACCEPTED;
}
2012-09-16 20:24:00 -03:00
break;
2012-09-09 22:42:30 -03:00
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
2013-09-03 22:59:16 -03:00
if (packet.param1 == 1 || packet.param1 == 3) {
// when packet.param1 == 3 we reboot to hold in bootloader
hal.scheduler->reboot(packet.param1 == 3);
2012-09-09 22:42:30 -03:00
result = MAV_RESULT_ACCEPTED;
}
break;
2014-02-13 18:49:42 -04:00
case MAV_CMD_DO_FENCE_ENABLE:
result = MAV_RESULT_ACCEPTED;
if (!geofence_present()) {
result = MAV_RESULT_FAILED;
2014-03-25 22:42:58 -03:00
} switch((uint16_t)packet.param1) {
case 0:
2014-02-13 18:49:42 -04:00
if (! geofence_set_enabled(false, GCS_TOGGLED)) {
result = MAV_RESULT_FAILED;
}
2014-03-25 22:42:58 -03:00
break;
case 1:
2014-02-13 18:49:42 -04:00
if (! geofence_set_enabled(true, GCS_TOGGLED)) {
result = MAV_RESULT_FAILED;
}
2014-03-25 22:42:58 -03:00
break;
default:
result = MAV_RESULT_FAILED;
break;
2014-02-13 18:49:42 -04:00
}
break;
2012-08-21 23:19:51 -03:00
default:
2011-10-16 04:01:14 -03:00
break;
2012-08-21 23:19:51 -03:00
}
2014-03-18 17:33:37 -03:00
mavlink_msg_command_ack_send_buf(
msg,
2012-08-21 23:19:51 -03:00
chan,
packet.command,
result);
break;
}
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
case MAVLINK_MSG_ID_SET_MODE:
{
// decode
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// we ignore base_mode as there is no sane way to map
// from that bitmap to a APM flight mode. We rely on
// custom_mode instead.
2011-09-08 22:29:39 -03:00
break;
}
2012-08-21 23:19:51 -03:00
switch (packet.custom_mode) {
case MANUAL:
case CIRCLE:
case STABILIZE:
2012-12-04 02:32:37 -04:00
case TRAINING:
2013-07-10 10:25:38 -03:00
case ACRO:
2012-08-21 23:19:51 -03:00
case FLY_BY_WIRE_A:
2014-04-12 01:12:14 -03:00
case AUTOTUNE:
2012-08-21 23:19:51 -03:00
case FLY_BY_WIRE_B:
2013-07-13 07:05:53 -03:00
case CRUISE:
2012-08-21 23:19:51 -03:00
case AUTO:
case RTL:
case LOITER:
2012-11-30 17:15:48 -04:00
set_mode((enum FlightMode)packet.custom_mode);
2012-08-21 23:19:51 -03:00
break;
}
break;
}
2014-03-03 09:49:14 -04:00
// GCS request the full list of commands, we return just the number and leave the GCS to then request each command individually
2012-08-21 23:19:51 -03:00
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
{
2014-03-18 10:34:00 -03:00
handle_mission_request_list(mission, msg);
2012-08-21 23:19:51 -03:00
break;
}
2011-10-16 04:01:14 -03:00
2012-08-21 23:19:51 -03:00
// XXX read a WP from EEPROM and send it to the GCS
2012-08-08 23:22:46 -03:00
case MAVLINK_MSG_ID_MISSION_REQUEST:
2012-08-21 23:19:51 -03:00
{
2014-03-18 19:59:51 -03:00
handle_mission_request(mission, msg);
2012-08-21 23:19:51 -03:00
break;
}
2012-08-15 21:14:46 -03:00
2012-08-21 23:19:51 -03:00
case MAVLINK_MSG_ID_MISSION_ACK:
{
2014-03-18 18:34:35 -03:00
// nothing to do
2012-08-21 23:19:51 -03:00
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{
2013-11-08 07:27:22 -04:00
// mark the firmware version in the tlog
send_text_P(SEVERITY_LOW, PSTR(FIRMWARE_STRING));
2012-08-21 23:19:51 -03:00
2014-01-14 00:37:03 -04:00
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
send_text_P(SEVERITY_LOW, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
#endif
2014-03-18 18:34:35 -03:00
handle_param_request_list(msg);
2012-08-21 23:19:51 -03:00
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
{
2014-03-18 18:34:35 -03:00
handle_param_request_read(msg);
2012-08-21 23:19:51 -03:00
break;
}
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
{
2014-03-18 10:34:00 -03:00
handle_mission_clear_all(mission, msg);
2012-08-21 23:19:51 -03:00
break;
}
2011-09-08 22:29:39 -03:00
2012-08-08 23:22:46 -03:00
case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
2012-08-21 23:19:51 -03:00
{
2014-03-18 10:34:00 -03:00
handle_mission_set_current(mission, msg);
2014-03-20 20:21:37 -03:00
if (control_mode == AUTO && mission.state() == AP_Mission::MISSION_STOPPED) {
mission.resume();
}
2012-08-21 23:19:51 -03:00
break;
}
2011-09-08 22:29:39 -03:00
2014-03-03 09:49:14 -04:00
// GCS provides the full number of commands it wishes to upload
// individual commands will then be sent from the GCS using the MAVLINK_MSG_ID_MISSION_ITEM message
2012-08-08 23:22:46 -03:00
case MAVLINK_MSG_ID_MISSION_COUNT:
2012-08-21 23:19:51 -03:00
{
2014-03-18 10:34:00 -03:00
handle_mission_count(mission, msg);
2012-08-21 23:19:51 -03:00
break;
}
2012-08-09 03:20:13 -03:00
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
2012-08-21 23:19:51 -03:00
{
2014-03-18 10:34:00 -03:00
handle_mission_write_partial_list(mission, msg);
2012-08-21 23:19:51 -03:00
break;
}
2011-09-08 22:29:39 -03:00
#ifdef MAVLINK_MSG_ID_SET_MAG_OFFSETS
case MAVLINK_MSG_ID_SET_MAG_OFFSETS:
{
mavlink_set_mag_offsets_t packet;
mavlink_msg_set_mag_offsets_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
compass.set_offsets(Vector3f(packet.mag_ofs_x, packet.mag_ofs_y, packet.mag_ofs_z));
break;
}
#endif
2014-03-03 09:49:14 -04:00
// GCS has sent us a command from GCS, store to EEPROM
2012-08-08 23:22:46 -03:00
case MAVLINK_MSG_ID_MISSION_ITEM:
2012-08-21 23:19:51 -03:00
{
2014-03-18 19:59:51 -03:00
handle_mission_item(msg, mission);
2012-08-21 23:19:51 -03:00
break;
}
2011-09-08 22:29:39 -03:00
2011-12-15 03:09:29 -04:00
#if GEOFENCE_ENABLED == ENABLED
2012-08-21 23:19:51 -03:00
// receive a fence point from GCS and store in EEPROM
2011-12-15 03:09:29 -04:00
case MAVLINK_MSG_ID_FENCE_POINT: {
mavlink_fence_point_t packet;
2011-12-15 22:48:15 -04:00
mavlink_msg_fence_point_decode(msg, &packet);
2011-12-15 21:41:11 -04:00
if (mavlink_check_target(packet.target_system, packet.target_component))
break;
2011-12-15 03:09:29 -04:00
if (g.fence_action != FENCE_ACTION_NONE) {
2012-12-12 17:59:31 -04:00
send_text_P(SEVERITY_LOW,PSTR("fencing must be disabled"));
2011-12-15 03:09:29 -04:00
} else if (packet.count != g.fence_total) {
2012-12-12 17:59:31 -04:00
send_text_P(SEVERITY_LOW,PSTR("bad fence point"));
2011-12-15 03:09:29 -04:00
} else {
2011-12-15 22:48:15 -04:00
Vector2l point;
point.x = packet.lat*1.0e7;
point.y = packet.lng*1.0e7;
2011-12-15 03:09:29 -04:00
set_fence_point_with_index(point, packet.idx);
}
break;
}
2012-08-21 23:19:51 -03:00
// send a fence point to GCS
2011-12-15 03:09:29 -04:00
case MAVLINK_MSG_ID_FENCE_FETCH_POINT: {
mavlink_fence_fetch_point_t packet;
2011-12-15 22:48:15 -04:00
mavlink_msg_fence_fetch_point_decode(msg, &packet);
2011-12-15 21:41:11 -04:00
if (mavlink_check_target(packet.target_system, packet.target_component))
break;
2011-12-15 03:09:29 -04:00
if (packet.idx >= g.fence_total) {
2012-12-12 17:59:31 -04:00
send_text_P(SEVERITY_LOW,PSTR("bad fence point"));
2011-12-15 03:09:29 -04:00
} else {
2011-12-15 22:48:15 -04:00
Vector2l point = get_fence_point_with_index(packet.idx);
2014-03-18 17:33:37 -03:00
mavlink_msg_fence_point_send_buf(msg, chan, msg->sysid, msg->compid, packet.idx, g.fence_total,
point.x*1.0e-7, point.y*1.0e-7);
2011-12-15 03:09:29 -04:00
}
break;
}
#endif // GEOFENCE_ENABLED
2013-09-22 01:45:24 -03:00
// receive a rally point from GCS and store in EEPROM
case MAVLINK_MSG_ID_RALLY_POINT: {
mavlink_rally_point_t packet;
mavlink_msg_rally_point_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component))
break;
2014-04-18 16:19:13 -03:00
if (packet.idx >= rally.get_rally_total() ||
2013-10-02 23:20:54 -03:00
packet.idx >= MAX_RALLYPOINTS) {
send_text_P(SEVERITY_LOW,PSTR("bad rally point message ID"));
break;
}
2014-04-18 16:19:13 -03:00
if (packet.count != rally.get_rally_total()) {
2013-10-02 23:20:54 -03:00
send_text_P(SEVERITY_LOW,PSTR("bad rally point message count"));
break;
2013-09-22 01:45:24 -03:00
}
2013-10-02 23:20:54 -03:00
RallyLocation rally_point;
rally_point.lat = packet.lat;
rally_point.lng = packet.lng;
rally_point.alt = packet.alt;
rally_point.break_alt = packet.break_alt;
rally_point.land_dir = packet.land_dir;
rally_point.flags = packet.flags;
2014-04-18 16:19:13 -03:00
rally.set_rally_point_with_index(packet.idx, rally_point);
2013-09-22 01:45:24 -03:00
break;
}
//send a rally point to the GCS
case MAVLINK_MSG_ID_RALLY_FETCH_POINT: {
mavlink_rally_fetch_point_t packet;
mavlink_msg_rally_fetch_point_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component))
break;
2014-04-18 16:19:13 -03:00
if (packet.idx > rally.get_rally_total()) {
2013-10-02 23:20:54 -03:00
send_text_P(SEVERITY_LOW, PSTR("bad rally point index"));
break;
}
RallyLocation rally_point;
2014-04-18 16:19:13 -03:00
if (!rally.get_rally_point_with_index(packet.idx, rally_point)) {
2013-10-02 23:20:54 -03:00
send_text_P(SEVERITY_LOW, PSTR("failed to set rally point"));
break;
2013-09-22 01:45:24 -03:00
}
2014-03-18 17:33:37 -03:00
mavlink_msg_rally_point_send_buf(msg,
chan, msg->sysid, msg->compid, packet.idx,
2014-04-18 16:19:13 -03:00
rally.get_rally_total(), rally_point.lat, rally_point.lng,
2014-03-18 17:33:37 -03:00
rally_point.alt, rally_point.break_alt, rally_point.land_dir,
rally_point.flags);
2013-09-22 01:45:24 -03:00
break;
}
2011-09-08 22:29:39 -03:00
case MAVLINK_MSG_ID_PARAM_SET:
2012-08-21 23:19:51 -03:00
{
2014-03-18 18:34:35 -03:00
handle_param_set(msg, &DataFlash);
2012-08-21 23:19:51 -03:00
break;
2014-03-18 18:34:35 -03:00
}
2011-09-08 22:29:39 -03:00
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
2012-08-21 23:19:51 -03:00
{
// allow override of RC channel values for HIL
// or for complete GCS control of switch position
// and RC PWM values.
if(msg->sysid != g.sysid_my_gcs) break; // Only accept control from our gcs
mavlink_rc_channels_override_t packet;
int16_t v[8];
mavlink_msg_rc_channels_override_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component))
2011-09-08 22:29:39 -03:00
break;
2012-08-21 23:19:51 -03:00
v[0] = packet.chan1_raw;
v[1] = packet.chan2_raw;
v[2] = packet.chan3_raw;
v[3] = packet.chan4_raw;
v[4] = packet.chan5_raw;
v[5] = packet.chan6_raw;
v[6] = packet.chan7_raw;
v[7] = packet.chan8_raw;
2012-12-04 18:22:21 -04:00
2014-04-28 18:47:01 -03:00
if (hal.rcin->set_overrides(v, 8)) {
failsafe.last_valid_rc_ms = hal.scheduler->millis();
}
2012-12-04 18:22:21 -04:00
2012-12-25 17:46:36 -04:00
// a RC override message is consiered to be a 'heartbeat' from
// the ground station for failsafe purposes
2013-07-19 01:11:16 -03:00
failsafe.last_heartbeat_ms = millis();
2012-08-21 23:19:51 -03:00
break;
}
2011-09-08 22:29:39 -03:00
case MAVLINK_MSG_ID_HEARTBEAT:
2012-08-21 23:19:51 -03:00
{
2012-12-25 17:46:36 -04:00
// We keep track of the last time we received a heartbeat from
// our GCS for failsafe purposes
if (msg->sysid != g.sysid_my_gcs) break;
2013-07-19 01:11:16 -03:00
failsafe.last_heartbeat_ms = millis();
2012-08-21 23:19:51 -03:00
break;
}
2011-09-08 22:29:39 -03:00
2012-07-04 21:55:58 -03:00
#if HIL_MODE != HIL_MODE_DISABLED
2012-08-21 23:19:51 -03:00
case MAVLINK_MSG_ID_HIL_STATE:
{
mavlink_hil_state_t packet;
mavlink_msg_hil_state_decode(msg, &packet);
2013-11-22 19:47:34 -04:00
last_hil_state = packet;
2014-03-28 16:52:48 -03:00
// set gps hil sensor
Location loc;
loc.lat = packet.lat;
loc.lng = packet.lon;
loc.alt = packet.alt/10;
Vector3f vel(packet.vx, packet.vy, packet.vz);
vel *= 0.01f;
2014-04-01 17:50:25 -03:00
gps.setHIL(0, AP_GPS::GPS_OK_FIX_3D,
2014-03-28 16:52:48 -03:00
packet.time_usec/1000,
2014-04-01 17:50:25 -03:00
loc, vel, 10, 0, true);
2012-08-21 23:19:51 -03:00
// rad/sec
Vector3f gyros;
gyros.x = packet.rollspeed;
gyros.y = packet.pitchspeed;
gyros.z = packet.yawspeed;
// m/s/s
Vector3f accels;
2013-01-01 22:52:35 -04:00
accels.x = packet.xacc * (GRAVITY_MSS/1000.0);
accels.y = packet.yacc * (GRAVITY_MSS/1000.0);
accels.z = packet.zacc * (GRAVITY_MSS/1000.0);
2012-07-04 21:55:58 -03:00
2014-02-22 17:18:31 -04:00
ins.set_gyro(0, gyros);
ins.set_accel(0, accels);
2012-08-21 23:19:51 -03:00
2013-05-02 02:27:02 -03:00
barometer.setHIL(packet.alt*0.001f);
2013-05-02 02:00:59 -03:00
compass.setHIL(packet.roll, packet.pitch, packet.yaw);
2013-06-02 22:40:44 -03:00
airspeed.disable();
2013-11-22 21:37:05 -04:00
// cope with DCM getting badly off due to HIL lag
2013-11-23 03:27:20 -04:00
if (g.hil_err_limit > 0 &&
(fabsf(packet.roll - ahrs.roll) > ToRad(g.hil_err_limit) ||
fabsf(packet.pitch - ahrs.pitch) > ToRad(g.hil_err_limit) ||
wrap_PI(fabsf(packet.yaw - ahrs.yaw)) > ToRad(g.hil_err_limit))) {
2013-11-22 21:37:05 -04:00
ahrs.reset_attitude(packet.roll, packet.pitch, packet.yaw);
}
2012-08-21 23:19:51 -03:00
break;
}
2011-09-08 22:29:39 -03:00
#endif // HIL_MODE
2011-10-31 18:55:58 -03:00
2012-06-13 16:00:20 -03:00
#if CAMERA == ENABLED
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE:
2012-08-21 23:19:51 -03:00
{
2013-01-01 19:18:45 -04:00
camera.configure_msg(msg);
2012-08-21 23:19:51 -03:00
break;
}
2012-06-13 16:00:20 -03:00
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
2012-08-21 23:19:51 -03:00
{
2013-01-01 19:18:45 -04:00
camera.control_msg(msg);
2012-08-21 23:19:51 -03:00
break;
}
2012-06-13 16:00:20 -03:00
#endif // CAMERA == ENABLED
2011-10-31 18:55:58 -03:00
#if MOUNT == ENABLED
case MAVLINK_MSG_ID_MOUNT_CONFIGURE:
2012-08-21 23:19:51 -03:00
{
camera_mount.configure_msg(msg);
break;
}
2011-10-31 18:55:58 -03:00
case MAVLINK_MSG_ID_MOUNT_CONTROL:
2012-08-21 23:19:51 -03:00
{
camera_mount.control_msg(msg);
break;
}
2011-10-31 18:55:58 -03:00
case MAVLINK_MSG_ID_MOUNT_STATUS:
2012-08-21 23:19:51 -03:00
{
2014-06-17 23:04:53 -03:00
camera_mount.status_msg(msg, chan);
2012-08-21 23:19:51 -03:00
break;
}
2011-10-31 18:55:58 -03:00
#endif // MOUNT == ENABLED
2012-04-01 21:58:44 -03:00
case MAVLINK_MSG_ID_RADIO:
2013-08-24 04:59:02 -03:00
case MAVLINK_MSG_ID_RADIO_STATUS:
2012-08-21 23:19:51 -03:00
{
2014-03-11 14:05:49 -03:00
handle_radio_status(msg, DataFlash, should_log(MASK_LOG_PM));
2012-08-21 23:19:51 -03:00
break;
}
2012-04-01 21:58:44 -03:00
2014-01-13 22:51:49 -04:00
case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
case MAVLINK_MSG_ID_LOG_ERASE:
in_log_download = true;
// fallthru
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
if (!in_mavlink_delay) {
handle_log_message(msg, DataFlash);
}
break;
case MAVLINK_MSG_ID_LOG_REQUEST_END:
in_log_download = false;
2013-12-15 03:59:23 -04:00
if (!in_mavlink_delay) {
handle_log_message(msg, DataFlash);
}
break;
2014-04-04 17:08:05 -03:00
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
case MAVLINK_MSG_ID_SERIAL_CONTROL:
handle_serial_control(msg, gps);
break;
#endif
2012-08-30 23:09:24 -03:00
default:
// forward unknown messages to the other link if there is one
2013-11-22 04:18:19 -04:00
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised && i != (uint8_t)chan) {
mavlink_channel_t out_chan = (mavlink_channel_t)i;
// only forward if it would fit in the transmit buffer
if (comm_get_txspace(out_chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES) {
_mavlink_resend_uart(out_chan, msg);
}
2012-08-30 23:09:24 -03:00
}
}
break;
2011-09-08 22:29:39 -03:00
} // end switch
} // end handle mavlink
/*
2012-08-21 23:19:51 -03:00
* 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
*/
2012-12-04 18:22:21 -04:00
static void mavlink_delay_cb()
2011-09-08 22:29:39 -03:00
{
2012-08-18 06:26:13 -03:00
static uint32_t last_1hz, last_50hz, last_5s;
2014-01-13 23:29:14 -04:00
if (!gcs[0].initialised || in_mavlink_delay) return;
2011-09-08 22:29:39 -03:00
in_mavlink_delay = true;
2012-12-04 18:22:21 -04:00
uint32_t tnow = 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();
2013-08-29 00:13:58 -03:00
notify.update();
2012-12-04 18:22:21 -04:00
}
if (tnow - last_5s > 5000) {
last_5s = tnow;
gcs_send_text_P(SEVERITY_LOW, PSTR("Initialising APM..."));
}
check_usb_mux();
2011-09-08 22:29:39 -03:00
in_mavlink_delay = false;
}
2011-09-18 00:46:42 -03:00
/*
2012-08-21 23:19:51 -03:00
* send a message on both GCS links
2011-09-18 00:46:42 -03:00
*/
static void gcs_send_message(enum ap_message id)
{
2013-11-22 04:18:19 -04:00
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
gcs[i].send_message(id);
}
2011-11-20 05:31:45 -04:00
}
2011-09-18 00:46:42 -03:00
}
/*
2012-08-21 23:19:51 -03:00
* send data streams in the given rate range on both links
2011-09-18 00:46:42 -03:00
*/
2012-04-01 20:24:05 -03:00
static void gcs_data_stream_send(void)
2011-09-18 00:46:42 -03:00
{
2013-11-22 04:18:19 -04:00
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
gcs[i].data_stream_send();
}
2011-11-20 05:31:45 -04:00
}
2011-09-18 01:00:49 -03:00
}
/*
2012-08-21 23:19:51 -03:00
* look for incoming commands on the GCS links
2011-09-18 01:00:49 -03:00
*/
static void gcs_update(void)
{
2013-11-22 04:18:19 -04:00
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
2014-05-20 23:44:05 -03:00
#if CLI_ENABLED == ENABLED
gcs[i].update(run_cli);
#else
gcs[i].update(NULL);
#endif
2013-11-22 04:18:19 -04:00
}
2011-11-20 05:31:45 -04:00
}
2011-09-18 01:00:49 -03:00
}
2011-09-18 05:02:33 -03:00
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
2011-09-18 01:00:49 -03:00
{
2013-11-22 04:18:19 -04:00
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
gcs[i].send_text_P(severity, str);
}
2011-11-20 05:31:45 -04:00
}
2013-05-02 23:40:35 -03:00
#if LOGGING_ENABLED == ENABLED
2013-05-02 22:16:50 -03:00
DataFlash.Log_Write_Message_P(str);
2013-05-02 23:40:35 -03:00
#endif
2011-09-18 00:46:42 -03:00
}
2011-09-18 05:57:41 -03:00
/*
2012-08-21 23:19:51 -03:00
* send a low priority formatted message to the GCS
* only one fits in the queue, so if you send more than one before the
* last one gets into the serial buffer then the old one will be lost
2011-09-18 05:57:41 -03:00
*/
2012-08-14 03:54:56 -03:00
void gcs_send_text_fmt(const prog_char_t *fmt, ...)
2011-09-18 05:57:41 -03:00
{
2012-11-12 00:30:04 -04:00
va_list arg_list;
2013-11-22 04:18:19 -04:00
gcs[0].pending_status.severity = (uint8_t)SEVERITY_LOW;
2012-11-12 00:30:04 -04:00
va_start(arg_list, fmt);
2013-11-22 04:18:19 -04:00
hal.util->vsnprintf_P((char *)gcs[0].pending_status.text,
sizeof(gcs[0].pending_status.text), fmt, arg_list);
2012-11-12 00:30:04 -04:00
va_end(arg_list);
2013-05-02 23:40:35 -03:00
#if LOGGING_ENABLED == ENABLED
2013-11-22 04:18:19 -04:00
DataFlash.Log_Write_Message(gcs[0].pending_status.text);
2013-05-02 23:40:35 -03:00
#endif
2014-03-18 20:56:25 -03:00
gcs[0].send_message(MSG_STATUSTEXT);
2013-11-22 04:18:19 -04:00
for (uint8_t i=1; i<num_gcs; i++) {
if (gcs[i].initialised) {
gcs[i].pending_status = gcs[0].pending_status;
2014-03-18 20:56:25 -03:00
gcs[i].send_message(MSG_STATUSTEXT);
2013-11-22 04:18:19 -04:00
}
2011-12-03 18:06:08 -04:00
}
2011-09-18 05:57:41 -03:00
}
2012-04-24 09:18:30 -03:00
2013-08-28 09:36:59 -03:00
/*
send airspeed calibration data
*/
static void gcs_send_airspeed_calibration(const Vector3f &vg)
{
2013-11-22 04:18:19 -04:00
for (uint8_t i=0; i<num_gcs; i++) {
if (comm_get_txspace((mavlink_channel_t)i) - MAVLINK_NUM_NON_PAYLOAD_BYTES >=
2013-08-28 09:36:59 -03:00
MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN) {
2013-11-22 04:18:19 -04:00
airspeed.log_mavlink_send((mavlink_channel_t)i, vg);
2013-08-28 09:36:59 -03:00
}
}
}
2013-10-14 19:52:23 -03:00
/**
retry any deferred messages
*/
static void gcs_retry_deferred(void)
{
gcs_send_message(MSG_RETRY_DEFERRED);
}