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
#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)
2011-09-08 22:29:39 -03:00
// use this to prevent recursion during sensor init
static bool in_mavlink_delay;
2011-10-27 04:35:25 -03:00
// true when we have received at least 1 MAVLink packet
static bool mavlink_active;
2011-09-18 05:57:41 -03:00
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:
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
if (control_mode != INITIALISING) {
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
2011-09-18 03:39:09 -03:00
static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops)
{
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
}
if (airspeed.enabled() && airspeed.use()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
2011-10-16 04:01:14 -03:00
}
2013-07-12 22:27:39 -03:00
if (g_gps != NULL && g_gps->status() > 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
}
2013-10-04 00:33:31 -03:00
// all present sensors enabled by default except rate control, attitude stabilization, yaw, altitude, position control 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);
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:
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;
}
2013-10-04 00:33:31 -03:00
// default to all healthy except compass and gps which we set individually
control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS);
if (g.compass_enabled && compass.healthy && ahrs.use_compass()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
2012-11-11 20:26:54 -04:00
}
2013-10-04 00:33:31 -03:00
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
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_meminfo(mavlink_channel_t chan)
{
2013-01-01 22:52:35 -04:00
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
2011-09-18 03:39:09 -03:00
extern unsigned __brkval;
mavlink_msg_meminfo_send(chan, __brkval, memcheck_available_memory());
2012-12-12 17:59:31 -04:00
#endif
2011-09-18 03:39:09 -03:00
}
static void NOINLINE send_location(mavlink_channel_t chan)
{
2012-11-13 01:38:24 -04:00
uint32_t fix_time;
// 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.
2013-03-25 04:25:24 -03:00
if (g_gps->status() >= GPS::GPS_OK_FIX_2D) {
2012-11-13 01:38:24 -04:00
fix_time = g_gps->last_fix_time;
} else {
fix_time = millis();
}
2011-10-16 04:01:14 -03:00
mavlink_msg_global_position_int_send(
chan,
2012-11-13 01:38:24 -04:00
fix_time,
2011-10-16 04:01:14 -03:00
current_loc.lat, // in 1E7 degrees
current_loc.lng, // in 1E7 degrees
2013-07-10 01:03:03 -03:00
g_gps->altitude_cm * 10, // millimeters above sea level
2013-07-10 00:40:13 -03:00
relative_altitude() * 1.0e3, // millimeters above ground
2012-10-31 07:50:55 -03:00
g_gps->velocity_north() * 100, // X speed cm/s (+ve North)
g_gps->velocity_east() * 100, // Y speed cm/s (+ve East)
g_gps->velocity_down() * -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
}
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
{
2011-10-16 04:01:14 -03:00
mavlink_msg_gps_raw_int_send(
chan,
2012-05-23 04:29:52 -03:00
g_gps->last_fix_time*(uint64_t)1000,
2013-03-25 04:25:24 -03:00
g_gps->status(),
2011-10-16 04:01:14 -03:00
g_gps->latitude, // in 1E7 degrees
g_gps->longitude, // in 1E7 degrees
2013-07-10 01:03:03 -03:00
g_gps->altitude_cm * 10, // in mm
2011-10-16 04:01:14 -03:00
g_gps->hdop,
65535,
2013-07-10 01:03:03 -03:00
g_gps->ground_speed_cm, // cm/s
g_gps->ground_course_cd, // 1/100 degrees,
2011-10-16 04:01:14 -03:00
g_gps->num_sats);
2011-09-18 03:39:09 -03:00
}
2013-09-20 20:27:22 -03:00
#if HIL_MODE != HIL_MODE_DISABLED
2011-09-18 03:39:09 -03:00
static void NOINLINE send_servo_out(mavlink_channel_t chan)
{
// 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
2013-06-03 02:32:08 -03:00
10000 * channel_roll->norm_output(),
10000 * channel_pitch->norm_output(),
10000 * channel_throttle->norm_output(),
10000 * channel_rudder->norm_output(),
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_in(mavlink_channel_t chan)
{
mavlink_msg_rc_channels_raw_send(
2011-10-16 04:01:14 -03:00
chan,
millis(),
0, // port
2012-12-04 18:22:21 -04:00
hal.rcin->read(CH_1),
hal.rcin->read(CH_2),
hal.rcin->read(CH_3),
hal.rcin->read(CH_4),
hal.rcin->read(CH_5),
hal.rcin->read(CH_6),
hal.rcin->read(CH_7),
hal.rcin->read(CH_8),
2012-08-22 00:58:25 -03:00
receiver_rssi);
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,
2013-07-10 01:03:03 -03:00
(float)g_gps->ground_speed_cm * 0.01f,
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)
{
2012-11-05 00:32:13 -04:00
Vector3f accel = ins.get_accel();
Vector3f gyro = ins.get_gyro();
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,
compass.mag_x,
compass.mag_y,
compass.mag_z);
}
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
{
2012-03-11 05:13:31 -03:00
Vector3f omega_I = ahrs.get_gyro_drift();
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
}
// 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);
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,
board_voltage(),
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);
}
2011-09-18 03:39:09 -03:00
static void NOINLINE send_current_waypoint(mavlink_channel_t chan)
{
2012-08-08 23:22:46 -03:00
mavlink_msg_mission_current_send(
2011-09-18 03:39:09 -03:00
chan,
2011-10-25 22:27:23 -03:00
g.command_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)
{
2012-09-24 04:39:09 -03:00
mavlink_statustext_t *s = (chan == MAVLINK_COMM_0?&gcs0.pending_status:&gcs3.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
static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops)
{
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);
send_heartbeat(chan);
return true;
case MSG_EXTENDED_STATUS1:
CHECK_PAYLOAD_SIZE(SYS_STATUS);
send_extended_status1(chan, packet_drops);
break;
case MSG_EXTENDED_STATUS2:
CHECK_PAYLOAD_SIZE(MEMINFO);
send_meminfo(chan);
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);
2011-09-18 03:39:09 -03:00
send_gps_raw(chan);
break;
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);
send_radio_in(chan);
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);
if (chan == MAVLINK_COMM_0) {
gcs0.queued_param_send();
2011-11-20 05:31:45 -04:00
} else if (gcs3.initialised) {
2011-09-18 03:39:09 -03:00
gcs3.queued_param_send();
}
break;
case MSG_NEXT_WAYPOINT:
2012-08-08 23:22:46 -03:00
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
2011-09-18 03:39:09 -03:00
if (chan == MAVLINK_COMM_0) {
gcs0.queued_waypoint_send();
2011-11-20 05:31:45 -04:00
} else if (gcs3.initialised) {
2011-09-18 03:39:09 -03:00
gcs3.queued_waypoint_send();
}
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);
break;
case MSG_HWSTATUS:
CHECK_PAYLOAD_SIZE(HWSTATUS);
send_hwstatus(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
2012-08-21 23:19:51 -03:00
}
2011-09-18 03:39:09 -03:00
return true;
}
#define MAX_DEFERRED_MESSAGES MSG_RETRY_DEFERRED
static struct mavlink_queue {
enum ap_message deferred_messages[MAX_DEFERRED_MESSAGES];
uint8_t next_deferred_message;
uint8_t num_deferred_messages;
} mavlink_queue[2];
// send a message using mavlink
static void mavlink_send_message(mavlink_channel_t chan, enum ap_message id, uint16_t packet_drops)
{
uint8_t i, nextid;
struct mavlink_queue *q = &mavlink_queue[(uint8_t)chan];
// see if we can send the deferred messages, if any
while (q->num_deferred_messages != 0) {
if (!mavlink_try_send_message(chan,
q->deferred_messages[q->next_deferred_message],
packet_drops)) {
break;
}
q->next_deferred_message++;
if (q->next_deferred_message == MAX_DEFERRED_MESSAGES) {
q->next_deferred_message = 0;
}
q->num_deferred_messages--;
}
if (id == MSG_RETRY_DEFERRED) {
return;
}
// this message id might already be deferred
for (i=0, nextid = q->next_deferred_message; i < q->num_deferred_messages; i++) {
if (q->deferred_messages[nextid] == id) {
// its already deferred, discard
return;
}
nextid++;
if (nextid == MAX_DEFERRED_MESSAGES) {
nextid = 0;
}
}
if (q->num_deferred_messages != 0 ||
!mavlink_try_send_message(chan, id, packet_drops)) {
// can't send it now, so defer it
if (q->num_deferred_messages == MAX_DEFERRED_MESSAGES) {
// the defer buffer is full, discard
return;
}
nextid = q->next_deferred_message + q->num_deferred_messages;
if (nextid >= MAX_DEFERRED_MESSAGES) {
nextid -= MAX_DEFERRED_MESSAGES;
}
q->deferred_messages[nextid] = id;
q->num_deferred_messages++;
}
}
2011-09-18 05:02:33 -03:00
void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char *str)
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;
}
2011-09-18 05:03:51 -03:00
2011-09-18 05:57:41 -03:00
if (severity == SEVERITY_LOW) {
// send via the deferred queuing system
2012-09-24 04:39:09 -03:00
mavlink_statustext_t *s = (chan == MAVLINK_COMM_0?&gcs0.pending_status:&gcs3.pending_status);
s->severity = (uint8_t)severity;
strncpy((char *)s->text, str, sizeof(s->text));
2011-09-18 05:57:41 -03:00
mavlink_send_message(chan, MSG_STATUSTEXT, 0);
} else {
// send immediately
2011-10-16 04:01:14 -03:00
mavlink_msg_statustext_send(chan, severity, str);
2011-09-18 05:03:51 -03:00
}
2011-09-18 03:39:09 -03:00
}
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
};
GCS_MAVLINK::GCS_MAVLINK() :
packet_drops(0),
waypoint_send_timeout(1000), // 1 second
waypoint_receive_timeout(1000) // 1 second
2011-09-08 22:29:39 -03:00
{
2013-02-19 19:08:49 -04:00
AP_Param::setup_object_defaults(this, var_info);
2011-09-08 22:29:39 -03:00
}
void
2012-12-04 18:22:21 -04:00
GCS_MAVLINK::init(AP_HAL::UARTDriver *port)
2011-09-08 22:29:39 -03:00
{
GCS_Class::init(port);
2012-12-04 18:22:21 -04:00
if (port == (AP_HAL::BetterStream*)hal.uartA) {
2011-09-08 22:29:39 -03:00
mavlink_comm_0_port = port;
chan = MAVLINK_COMM_0;
}else{
mavlink_comm_1_port = port;
chan = MAVLINK_COMM_1;
}
2012-08-21 23:19:51 -03:00
_queued_parameter = NULL;
2012-12-04 18:22:21 -04:00
reset_cli_timeout();
2011-09-08 22:29:39 -03:00
}
void
GCS_MAVLINK::update(void)
{
// receive new packets
mavlink_message_t msg;
mavlink_status_t status;
2012-08-21 23:19:51 -03:00
status.packet_rx_drop_count = 0;
2011-09-08 22:29:39 -03:00
// process received bytes
2013-01-22 18:35:06 -04:00
uint16_t nbytes = comm_get_available(chan);
2013-01-22 19:06:22 -04:00
for (uint16_t i=0; i<nbytes; i++)
2011-09-08 22:29:39 -03:00
{
uint8_t c = comm_receive_ch(chan);
2011-10-27 04:35:25 -03:00
#if CLI_ENABLED == ENABLED
/* allow CLI to be started by hitting enter 3 times, if no
2012-08-21 23:19:51 -03:00
* heartbeat packets have been received */
2013-03-21 07:57:54 -03:00
if (mavlink_active == 0 && (millis() - _cli_timeout) < 20000 &&
comm_is_idle(chan)) {
2011-10-27 04:35:25 -03:00
if (c == '\n' || c == '\r') {
crlf_count++;
} else {
crlf_count = 0;
}
if (crlf_count == 3) {
2012-11-21 01:19:16 -04:00
run_cli(_port);
2011-10-27 04:35:25 -03:00
}
}
#endif
2011-09-08 22:29:39 -03:00
// Try to get a new message
2011-10-27 04:35:25 -03:00
if (mavlink_parse_char(chan, c, &msg, &status)) {
2012-11-20 23:11:05 -04:00
// we exclude radio packets to make it possible to use the
// CLI over the radio
2013-08-24 04:59:02 -03:00
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
2012-11-20 23:11:05 -04:00
mavlink_active = true;
}
2011-10-27 04:35:25 -03:00
handleMessage(&msg);
}
2011-09-08 22:29:39 -03:00
}
// Update packet drops counter
packet_drops += status.packet_rx_drop_count;
2012-09-22 06:38:05 -03:00
if (!waypoint_receiving) {
2011-10-31 07:25:35 -03:00
return;
}
uint32_t tnow = millis();
2011-09-18 03:39:09 -03:00
if (waypoint_receiving &&
2012-08-09 03:20:13 -03:00
waypoint_request_i <= waypoint_request_last &&
2012-04-01 21:58:44 -03:00
tnow > waypoint_timelast_request + 500 + (stream_slowdown*20)) {
2011-12-13 05:38:20 -04:00
waypoint_timelast_request = tnow;
2011-09-18 03:39:09 -03:00
send_message(MSG_NEXT_WAYPOINT);
}
2011-09-08 22:29:39 -03:00
// stop waypoint receiving if timeout
2012-08-21 23:19:51 -03:00
if (waypoint_receiving && (millis() - waypoint_timelast_receive) > waypoint_receive_timeout) {
2011-09-08 22:29:39 -03:00
waypoint_receiving = false;
}
}
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
2012-09-22 06:38:05 -03:00
if (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;
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);
send_message(MSG_GPS_RAW); // TODO - remove this message after location message is working
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);
2012-04-01 20:24:05 -03:00
}
2011-09-08 22:29:39 -03:00
}
2011-09-18 03:39:09 -03:00
2011-09-08 22:29:39 -03:00
void
2011-09-18 00:39:33 -03:00
GCS_MAVLINK::send_message(enum ap_message id)
2011-09-08 22:29:39 -03:00
{
mavlink_send_message(chan,id, packet_drops);
}
void
2012-12-12 17:59:31 -04:00
GCS_MAVLINK::send_text_P(gcs_severity severity, const prog_char_t *str)
2011-09-08 22:29:39 -03:00
{
mavlink_statustext_t m;
uint8_t i;
for (i=0; i<sizeof(m.text); i++) {
m.text[i] = pgm_read_byte((const prog_char *)(str++));
2013-05-20 00:51:16 -03:00
if (m.text[i] == '\0') {
break;
}
2011-09-08 22:29:39 -03:00
}
if (i < sizeof(m.text)) m.text[i] = 0;
mavlink_send_text(chan, severity, (const char *)m.text);
}
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
{
struct Location tell_command = {}; // command for telemetry
switch (msg->msgid) {
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
2012-08-21 23:19:51 -03:00
{
// decode
mavlink_request_data_stream_t packet;
mavlink_msg_request_data_stream_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
int16_t freq = 0; // packet frequency
2011-10-16 04:01:14 -03:00
2012-08-21 23:19:51 -03:00
if (packet.start_stop == 0)
freq = 0; // stop sending
else if (packet.start_stop == 1)
freq = packet.req_message_rate; // start sending
else
break;
2011-10-16 04:01:14 -03:00
2013-02-19 18:30:46 -04:00
switch (packet.req_stream_id) {
case MAV_DATA_STREAM_ALL:
2013-02-04 17:20:15 -04:00
// note that we don't set STREAM_PARAMS - that is internal only
for (uint8_t i=0; i<STREAM_PARAMS; i++) {
streamRates[i].set_and_save_ifchanged(freq);
2012-09-20 18:54:21 -03:00
}
2013-02-19 18:30:46 -04:00
break;
case MAV_DATA_STREAM_RAW_SENSORS:
streamRates[STREAM_RAW_SENSORS].set_and_save_ifchanged(freq);
break;
case MAV_DATA_STREAM_EXTENDED_STATUS:
streamRates[STREAM_EXTENDED_STATUS].set_and_save_ifchanged(freq);
break;
case MAV_DATA_STREAM_RC_CHANNELS:
streamRates[STREAM_RC_CHANNELS].set_and_save_ifchanged(freq);
break;
case MAV_DATA_STREAM_RAW_CONTROLLER:
streamRates[STREAM_RAW_CONTROLLER].set_and_save_ifchanged(freq);
break;
case MAV_DATA_STREAM_POSITION:
streamRates[STREAM_POSITION].set_and_save_ifchanged(freq);
break;
case MAV_DATA_STREAM_EXTRA1:
streamRates[STREAM_EXTRA1].set_and_save_ifchanged(freq);
break;
case MAV_DATA_STREAM_EXTRA2:
streamRates[STREAM_EXTRA2].set_and_save_ifchanged(freq);
break;
case MAV_DATA_STREAM_EXTRA3:
streamRates[STREAM_EXTRA3].set_and_save_ifchanged(freq);
break;
2011-10-16 04:01:14 -03:00
}
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
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:
2013-03-30 00:38:43 -03:00
servo_write(packet.param1 - 1, packet.param2);
2012-09-03 07:56:36 -03:00
result = MAV_RESULT_ACCEPTED;
break;
2012-08-21 23:19:51 -03:00
2012-09-16 20:24:00 -03:00
case MAV_CMD_DO_REPEAT_SERVO:
do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4);
result = MAV_RESULT_ACCEPTED;
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;
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
}
mavlink_msg_command_ack_send(
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:
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;
}
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
{
// decode
mavlink_mission_request_list_t packet;
mavlink_msg_mission_request_list_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component))
break;
// Start sending waypoints
mavlink_msg_mission_count_send(
chan,msg->sysid,
msg->compid,
g.command_total + 1); // + home
waypoint_timelast_send = millis();
waypoint_receiving = false;
waypoint_dest_sysid = msg->sysid;
waypoint_dest_compid = msg->compid;
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
{
// decode
mavlink_mission_request_t packet;
mavlink_msg_mission_request_decode(msg, &packet);
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
if (mavlink_check_target(packet.target_system, packet.target_component))
break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// send waypoint
2012-09-09 20:40:29 -03:00
tell_command = get_cmd_with_index_raw(packet.seq);
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// set frame of waypoint
uint8_t frame;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
if (tell_command.options & MASK_OPTIONS_RELATIVE_ALT) {
frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; // reference frame
} else {
frame = MAV_FRAME_GLOBAL; // reference frame
}
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
float param1 = 0, param2 = 0, param3 = 0, param4 = 0;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// time that the mav should loiter in milliseconds
uint8_t current = 0; // 1 (true), 0 (false)
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
if (packet.seq == (uint16_t)g.command_index)
current = 1;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
uint8_t autocontinue = 1; // 1 (true), 0 (false)
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
float x = 0, y = 0, z = 0;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
if (tell_command.id < MAV_CMD_NAV_LAST || tell_command.id == MAV_CMD_CONDITION_CHANGE_ALT) {
// command needs scaling
x = tell_command.lat/1.0e7; // local (x), global (latitude)
y = tell_command.lng/1.0e7; // local (y), global (longitude)
2012-09-09 20:40:29 -03:00
z = tell_command.alt/1.0e2;
2011-09-08 22:29:39 -03:00
}
2011-10-23 22:21:26 -03:00
2012-08-21 23:19:51 -03:00
switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields
2011-09-08 22:29:39 -03:00
2013-01-13 09:29:53 -04:00
case MAV_CMD_NAV_LOITER_TIME:
2012-08-21 23:19:51 -03:00
case MAV_CMD_NAV_LOITER_TURNS:
2013-01-13 09:29:53 -04:00
if (tell_command.options & MASK_OPTIONS_LOITER_DIRECTION) {
2013-04-14 09:04:25 -03:00
param3 = -abs(g.loiter_radius);
2013-01-13 09:29:53 -04:00
} else {
2013-04-14 09:04:25 -03:00
param3 = abs(g.loiter_radius);
2013-01-13 09:29:53 -04:00
}
2012-08-21 23:19:51 -03:00
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_DO_SET_HOME:
param1 = tell_command.p1;
break;
2011-09-08 22:29:39 -03:00
2013-01-13 09:29:53 -04:00
case MAV_CMD_NAV_LOITER_UNLIM:
if (tell_command.options & MASK_OPTIONS_LOITER_DIRECTION) {
2013-04-14 09:04:25 -03:00
param3 = -abs(g.loiter_radius);
2013-01-13 09:29:53 -04:00
} else {
2013-04-14 09:04:25 -03:00
param3 = abs(g.loiter_radius);
2013-01-13 09:29:53 -04:00
}
break;
2012-08-21 23:19:51 -03:00
case MAV_CMD_CONDITION_CHANGE_ALT:
x=0; // Clear fields loaded above that we don't want sent for this command
y=0;
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_CONDITION_DISTANCE:
param1 = tell_command.lat;
2011-09-08 22:29:39 -03:00
break;
2012-08-21 23:19:51 -03:00
case MAV_CMD_DO_JUMP:
param2 = tell_command.lat;
param1 = tell_command.p1;
break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
case MAV_CMD_DO_REPEAT_SERVO:
param4 = tell_command.lng;
case MAV_CMD_DO_REPEAT_RELAY:
case MAV_CMD_DO_CHANGE_SPEED:
param3 = tell_command.lat;
param2 = tell_command.alt;
param1 = tell_command.p1;
break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
case MAV_CMD_DO_SET_PARAMETER:
case MAV_CMD_DO_SET_RELAY:
case MAV_CMD_DO_SET_SERVO:
param2 = tell_command.alt;
param1 = tell_command.p1;
2011-09-08 22:29:39 -03:00
break;
}
2012-08-21 23:19:51 -03:00
mavlink_msg_mission_item_send(chan,msg->sysid,
msg->compid,
packet.seq,
frame,
tell_command.id,
current,
autocontinue,
param1,
param2,
param3,
param4,
x,
y,
z);
// update last waypoint comm stamp
waypoint_timelast_send = millis();
break;
}
2012-08-15 21:14:46 -03:00
2012-08-21 23:19:51 -03:00
case MAVLINK_MSG_ID_MISSION_ACK:
{
// decode
mavlink_mission_ack_t packet;
mavlink_msg_mission_ack_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{
// decode
mavlink_param_request_list_t packet;
mavlink_msg_param_request_list_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
// Start sending parameters - next call to ::update will kick the first one out
_queued_parameter = AP_Param::first(&_queued_parameter_token, &_queued_parameter_type);
_queued_parameter_index = 0;
_queued_parameter_count = _count_parameters();
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
{
// decode
mavlink_param_request_read_t packet;
mavlink_msg_param_request_read_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
enum ap_var_type p_type;
2012-09-19 18:42:46 -03:00
AP_Param *vp;
2013-01-21 01:52:08 -04:00
char param_name[AP_MAX_NAME_SIZE+1];
2012-09-19 18:42:46 -03:00
if (packet.param_index != -1) {
2013-01-08 18:45:45 -04:00
AP_Param::ParamToken token;
vp = AP_Param::find_by_index(packet.param_index, &p_type, &token);
2012-09-19 18:42:46 -03:00
if (vp == NULL) {
gcs_send_text_fmt(PSTR("Unknown parameter index %d"), packet.param_index);
break;
}
2013-04-19 04:53:52 -03:00
vp->copy_name_token(token, param_name, AP_MAX_NAME_SIZE, true);
2013-01-21 01:52:08 -04:00
param_name[AP_MAX_NAME_SIZE] = 0;
2012-09-19 18:42:46 -03:00
} else {
2013-01-21 01:52:08 -04:00
strncpy(param_name, packet.param_id, AP_MAX_NAME_SIZE);
param_name[AP_MAX_NAME_SIZE] = 0;
vp = AP_Param::find(param_name, &p_type);
2012-09-19 18:42:46 -03:00
if (vp == NULL) {
2012-11-20 06:36:13 -04:00
gcs_send_text_fmt(PSTR("Unknown parameter %.16s"), packet.param_id);
2012-09-19 18:42:46 -03:00
break;
}
2011-09-08 22:29:39 -03:00
}
2012-08-21 23:19:51 -03:00
float value = vp->cast_to_float(p_type);
mavlink_msg_param_value_send(
chan,
param_name,
value,
mav_var_type(p_type),
2012-09-22 03:53:12 -03:00
_count_parameters(),
packet.param_index);
2012-08-21 23:19:51 -03:00
break;
}
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
{
// decode
mavlink_mission_clear_all_t packet;
mavlink_msg_mission_clear_all_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component)) break;
// clear all commands
g.command_total.set_and_save(0);
// note that we don't send multiple acks, as otherwise a
// GCS that is doing a clear followed by a set may see
// the additional ACKs as ACKs of the set operations
mavlink_msg_mission_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ACCEPTED);
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
{
// decode
mavlink_mission_set_current_t packet;
mavlink_msg_mission_set_current_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// set current command
change_command(packet.seq);
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
mavlink_msg_mission_current_send(chan, g.command_index);
break;
}
2011-09-08 22:29:39 -03:00
2012-08-08 23:22:46 -03:00
case MAVLINK_MSG_ID_MISSION_COUNT:
2012-08-21 23:19:51 -03:00
{
// decode
mavlink_mission_count_t packet;
mavlink_msg_mission_count_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// start waypoint receiving
if (packet.count > MAX_WAYPOINTS) {
packet.count = MAX_WAYPOINTS;
2012-08-09 03:20:13 -03:00
}
2012-08-21 23:19:51 -03:00
g.command_total.set_and_save(packet.count - 1);
waypoint_timelast_receive = millis();
waypoint_timelast_request = 0;
waypoint_receiving = true;
waypoint_request_i = 0;
waypoint_request_last= g.command_total;
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
{
// decode
mavlink_mission_write_partial_list_t packet;
mavlink_msg_mission_write_partial_list_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
2012-08-09 03:20:13 -03:00
2012-08-21 23:19:51 -03:00
// start waypoint receiving
2012-09-16 02:05:48 -03:00
if (packet.start_index > g.command_total ||
2012-08-21 23:19:51 -03:00
packet.end_index > g.command_total ||
packet.end_index < packet.start_index) {
2012-12-12 17:59:31 -04:00
send_text_P(SEVERITY_LOW,PSTR("flight plan update rejected"));
2011-09-08 22:29:39 -03:00
break;
}
2012-08-21 23:19:51 -03:00
waypoint_timelast_receive = millis();
waypoint_timelast_request = 0;
waypoint_receiving = true;
waypoint_request_i = packet.start_index;
waypoint_request_last= packet.end_index;
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
2012-08-21 23:19:51 -03:00
// XXX receive a WP from GCS and store in EEPROM
2012-08-08 23:22:46 -03:00
case MAVLINK_MSG_ID_MISSION_ITEM:
2012-08-21 23:19:51 -03:00
{
// decode
mavlink_mission_item_t packet;
uint8_t result = MAV_MISSION_ACCEPTED;
mavlink_msg_mission_item_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
// defaults
tell_command.id = packet.command;
switch (packet.frame)
{
case MAV_FRAME_MISSION:
case MAV_FRAME_GLOBAL:
2011-09-08 22:29:39 -03:00
{
2013-01-10 14:42:24 -04:00
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
2012-08-21 23:19:51 -03:00
tell_command.options = 0; // absolute altitude
break;
}
2011-09-08 22:29:39 -03:00
2011-10-23 22:21:26 -03:00
#ifdef MAV_FRAME_LOCAL_NED
2012-08-21 23:19:51 -03:00
case MAV_FRAME_LOCAL_NED: // local (relative to home position)
{
2013-01-10 14:42:24 -04:00
tell_command.lat = 1.0e7f*ToDeg(packet.x/
2013-04-15 01:55:58 -03:00
(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat;
tell_command.lng = 1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng;
2013-01-10 14:42:24 -04:00
tell_command.alt = -packet.z*1.0e2f;
2012-08-21 23:19:51 -03:00
tell_command.options = MASK_OPTIONS_RELATIVE_ALT;
break;
}
2011-10-23 22:21:26 -03:00
#endif
#ifdef MAV_FRAME_LOCAL
2012-08-21 23:19:51 -03:00
case MAV_FRAME_LOCAL: // local (relative to home position)
{
2013-01-10 14:42:24 -04:00
tell_command.lat = 1.0e7f*ToDeg(packet.x/
2013-04-15 01:55:58 -03:00
(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat;
tell_command.lng = 1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng;
2013-01-10 14:42:24 -04:00
tell_command.alt = packet.z*1.0e2f;
2012-08-21 23:19:51 -03:00
tell_command.options = MASK_OPTIONS_RELATIVE_ALT;
break;
}
2011-10-23 22:21:26 -03:00
#endif
2012-08-21 23:19:51 -03:00
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude
{
2013-01-10 14:42:24 -04:00
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;
2012-08-21 23:19:51 -03:00
tell_command.options = MASK_OPTIONS_RELATIVE_ALT; // store altitude relative!! Always!!
break;
}
2011-10-25 22:18:24 -03:00
2012-08-21 23:19:51 -03:00
default:
result = MAV_MISSION_UNSUPPORTED_FRAME;
break;
}
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
if (result != MAV_MISSION_ACCEPTED) goto mission_failed;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// Switch to map APM command fields into MAVLink command fields
switch (tell_command.id) {
case MAV_CMD_NAV_LOITER_UNLIM:
2013-01-13 09:29:53 -04:00
if (packet.param3 < 0) {
tell_command.options |= MASK_OPTIONS_LOITER_DIRECTION;
}
case MAV_CMD_NAV_WAYPOINT:
2012-08-21 23:19:51 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
case MAV_CMD_NAV_LAND:
break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
case MAV_CMD_NAV_LOITER_TURNS:
2013-01-13 09:29:53 -04:00
case MAV_CMD_NAV_LOITER_TIME:
if (packet.param3 < 0) {
tell_command.options |= MASK_OPTIONS_LOITER_DIRECTION;
}
2012-08-21 23:19:51 -03:00
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_DO_SET_HOME:
tell_command.p1 = packet.param1;
break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
case MAV_CMD_CONDITION_CHANGE_ALT:
tell_command.lat = packet.param1;
break;
2011-10-23 22:21:26 -03:00
2012-08-21 23:19:51 -03:00
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_CONDITION_DISTANCE:
tell_command.lat = packet.param1;
break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
case MAV_CMD_DO_JUMP:
tell_command.lat = packet.param2;
tell_command.p1 = packet.param1;
break;
2011-10-23 22:21:26 -03:00
2012-08-21 23:19:51 -03:00
case MAV_CMD_DO_REPEAT_SERVO:
tell_command.lng = packet.param4;
case MAV_CMD_DO_REPEAT_RELAY:
case MAV_CMD_DO_CHANGE_SPEED:
tell_command.lat = packet.param3;
tell_command.alt = packet.param2;
tell_command.p1 = packet.param1;
break;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
case MAV_CMD_DO_SET_PARAMETER:
case MAV_CMD_DO_SET_RELAY:
case MAV_CMD_DO_SET_SERVO:
tell_command.alt = packet.param2;
tell_command.p1 = packet.param1;
break;
2011-09-08 22:29:39 -03:00
2013-04-01 22:56:19 -03:00
case MAV_CMD_DO_DIGICAM_CONTROL:
break;
2012-08-21 23:19:51 -03:00
default:
result = MAV_MISSION_UNSUPPORTED;
break;
}
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
if (result != MAV_MISSION_ACCEPTED) goto mission_failed;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
if(packet.current == 2) { //current = 2 is a flag to tell us this is a "guided mode" waypoint and not for the mission
guided_WP = tell_command;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// add home alt if needed
if (guided_WP.options & MASK_OPTIONS_RELATIVE_ALT) {
guided_WP.alt += home.alt;
}
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
set_mode(GUIDED);
2011-10-23 22:21:26 -03:00
2012-08-21 23:19:51 -03:00
// make any new wp uploaded instant (in case we are already in Guided mode)
set_guided_WP();
2011-10-23 22:21:26 -03:00
2012-08-21 23:19:51 -03:00
// verify we recevied the command
2012-08-08 23:22:46 -03:00
mavlink_msg_mission_ack_send(
2011-10-23 22:21:26 -03:00
chan,
msg->sysid,
msg->compid,
2012-08-21 23:19:51 -03:00
0);
2012-09-29 20:29:33 -03:00
} else if(packet.current == 3) { //current = 3 is a flag to tell us this is a alt change only
// add home alt if needed
if (tell_command.options & MASK_OPTIONS_RELATIVE_ALT) {
tell_command.alt += home.alt;
}
next_WP.alt = tell_command.alt;
// verify we recevied the command
mavlink_msg_mission_ack_send(
chan,
msg->sysid,
msg->compid,
0);
2012-08-21 23:19:51 -03:00
} else {
// Check if receiving waypoints (mission upload expected)
if (!waypoint_receiving) {
result = MAV_MISSION_ERROR;
goto mission_failed;
}
// check if this is the requested waypoint
if (packet.seq != waypoint_request_i) {
result = MAV_MISSION_INVALID_SEQUENCE;
goto mission_failed;
}
set_cmd_with_index(tell_command, packet.seq);
// update waypoint receiving state machine
waypoint_timelast_receive = millis();
waypoint_timelast_request = 0;
waypoint_request_i++;
if (waypoint_request_i > waypoint_request_last) {
mavlink_msg_mission_ack_send(
chan,
msg->sysid,
msg->compid,
result);
2012-12-12 17:59:31 -04:00
send_text_P(SEVERITY_LOW,PSTR("flight plan received"));
2012-08-21 23:19:51 -03:00
waypoint_receiving = false;
// XXX ignores waypoint radius for individual waypoints, can
// only set WP_RADIUS parameter
}
2011-09-08 22:29:39 -03:00
}
2012-08-21 23:19:51 -03:00
break;
mission_failed:
// we are rejecting the mission/waypoint
mavlink_msg_mission_ack_send(
chan,
msg->sysid,
msg->compid,
result);
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);
2013-03-12 01:04:48 -03:00
mavlink_msg_fence_point_send(chan, msg->sysid, msg->compid, packet.idx, g.fence_total,
2011-12-15 22:48:15 -04:00
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;
2013-10-02 23:20:54 -03:00
if (packet.idx >= g.rally_total ||
packet.idx >= MAX_RALLYPOINTS) {
send_text_P(SEVERITY_LOW,PSTR("bad rally point message ID"));
break;
}
2013-09-22 01:45:24 -03:00
if (packet.count != g.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;
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;
if (packet.idx > g.rally_total) {
2013-10-02 23:20:54 -03:00
send_text_P(SEVERITY_LOW, PSTR("bad rally point index"));
break;
}
RallyLocation rally_point;
if (!get_rally_point_with_index(packet.idx, rally_point)) {
send_text_P(SEVERITY_LOW, PSTR("failed to set rally point"));
break;
2013-09-22 01:45:24 -03:00
}
2013-10-02 23:20:54 -03:00
mavlink_msg_rally_point_send(chan, msg->sysid, msg->compid, packet.idx,
g.rally_total, rally_point.lat, rally_point.lng,
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
{
AP_Param *vp;
enum ap_var_type var_type;
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
// decode
mavlink_param_set_t packet;
mavlink_msg_param_set_decode(msg, &packet);
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
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
// set parameter
2012-11-20 06:36:13 -04:00
char key[AP_MAX_NAME_SIZE+1];
strncpy(key, (char *)packet.param_id, AP_MAX_NAME_SIZE);
key[AP_MAX_NAME_SIZE] = 0;
2012-08-21 23:19:51 -03:00
// find the requested parameter
vp = AP_Param::find(key, &var_type);
if ((NULL != vp) && // exists
!isnan(packet.param_value) && // not nan
!isinf(packet.param_value)) { // not inf
// add a small amount before casting parameter values
// from float to integer to avoid truncating to the
// next lower integer value.
float rounding_addition = 0.01;
// handle variables with standard type IDs
if (var_type == AP_PARAM_FLOAT) {
((AP_Float *)vp)->set_and_save(packet.param_value);
} else if (var_type == AP_PARAM_INT32) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
float v = packet.param_value+rounding_addition;
2013-05-01 21:27:10 -03:00
v = constrain_float(v, -2147483648.0, 2147483647.0);
2012-08-21 23:19:51 -03:00
((AP_Int32 *)vp)->set_and_save(v);
} else if (var_type == AP_PARAM_INT16) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
float v = packet.param_value+rounding_addition;
2013-05-01 21:27:10 -03:00
v = constrain_float(v, -32768, 32767);
2012-08-21 23:19:51 -03:00
((AP_Int16 *)vp)->set_and_save(v);
} else if (var_type == AP_PARAM_INT8) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
float v = packet.param_value+rounding_addition;
2013-05-01 21:27:10 -03:00
v = constrain_float(v, -128, 127);
2012-08-21 23:19:51 -03:00
((AP_Int8 *)vp)->set_and_save(v);
} else {
// we don't support mavlink set on this parameter
break;
}
// Report back the new value if we accepted the change
// we send the value we actually set, which could be
// different from the value sent, in case someone sent
// a fractional value to an integer type
mavlink_msg_param_value_send(
chan,
key,
vp->cast_to_float(var_type),
mav_var_type(var_type),
_count_parameters(),
-1); // XXX we don't actually know what its index is...
2013-04-20 05:21:10 -03:00
#if LOGGING_ENABLED == ENABLED
2013-04-19 20:50:52 -03:00
DataFlash.Log_Write_Parameter(key, vp->cast_to_float(var_type));
2013-04-20 05:21:10 -03:00
#endif
2012-08-21 23:19:51 -03:00
}
break;
} // end case
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
hal.rcin->set_overrides(v, 8);
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);
2012-12-18 22:36:00 -04:00
float vel = pythagorous2(packet.vx, packet.vy);
2013-01-10 14:42:24 -04:00
float cog = wrap_360_cd(ToDeg(atan2f(packet.vy, packet.vx)) * 100);
2012-08-21 23:19:51 -03:00
2013-01-03 21:47:08 -04:00
if (g_gps != NULL) {
// set gps hil sensor
g_gps->setHIL(packet.time_usec/1000,
packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3,
vel*1.0e-2, cog*1.0e-2, 0, 10);
}
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
2012-12-03 08:26:39 -04:00
ins.set_gyro(gyros);
ins.set_accel(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();
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
{
camera_mount.status_msg(msg);
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
{
mavlink_radio_t packet;
mavlink_msg_radio_decode(msg, &packet);
// use the state of the transmit buffer in the radio to
// control the stream rate, giving us adaptive software
// flow control
if (packet.txbuf < 20 && stream_slowdown < 100) {
// we are very low on space - slow down a lot
stream_slowdown += 3;
} else if (packet.txbuf < 50 && stream_slowdown < 100) {
// we are a bit low on space, slow down slightly
stream_slowdown += 1;
} else if (packet.txbuf > 95 && stream_slowdown > 10) {
// the buffer has plenty of space, speed up a lot
stream_slowdown -= 2;
} else if (packet.txbuf > 90 && stream_slowdown != 0) {
// the buffer has enough space, speed up a bit
stream_slowdown--;
2012-04-01 21:58:44 -03:00
}
2012-08-21 23:19:51 -03:00
break;
}
2012-04-01 21:58:44 -03:00
2012-08-30 23:09:24 -03:00
default:
// forward unknown messages to the other link if there is one
if ((chan == MAVLINK_COMM_1 && gcs0.initialised) ||
(chan == MAVLINK_COMM_0 && gcs3.initialised)) {
mavlink_channel_t out_chan = (mavlink_channel_t)(((uint8_t)chan)^1);
// only forward if it would fit in our transmit buffer
2012-09-24 18:21:03 -03:00
if (comm_get_txspace(out_chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES) {
2012-08-30 23:09:24 -03:00
_mavlink_resend_uart(out_chan, msg);
}
}
break;
2011-09-08 22:29:39 -03:00
} // end switch
} // end handle mavlink
uint16_t
GCS_MAVLINK::_count_parameters()
{
// if we haven't cached the parameter count yet...
if (0 == _parameter_count) {
2012-02-12 04:20:56 -04:00
AP_Param *vp;
2012-02-19 01:58:08 -04:00
AP_Param::ParamToken token;
2011-09-08 22:29:39 -03:00
2012-02-12 04:20:56 -04:00
vp = AP_Param::first(&token, NULL);
2011-09-08 22:29:39 -03:00
do {
2012-02-12 04:20:56 -04:00
_parameter_count++;
} while (NULL != (vp = AP_Param::next_scalar(&token, NULL)));
2011-09-08 22:29:39 -03:00
}
return _parameter_count;
}
/**
2012-08-21 23:19:51 -03:00
* @brief Send the next pending parameter, called from deferred message
* handling code
*/
2011-09-08 22:29:39 -03:00
void
2011-09-18 03:39:09 -03:00
GCS_MAVLINK::queued_param_send()
2011-09-08 22:29:39 -03:00
{
2012-09-19 18:29:23 -03:00
if (_queued_parameter == NULL) {
return;
}
uint16_t bytes_allowed;
uint8_t count;
uint32_t tnow = millis();
2011-09-08 22:29:39 -03:00
2012-09-19 18:29:23 -03:00
// use at most 30% of bandwidth on parameters. The constant 26 is
// 1/(1000 * 1/8 * 0.001 * 0.3)
bytes_allowed = g.serial3_baud * (tnow - _queued_parameter_send_time_ms) * 26;
if (bytes_allowed > comm_get_txspace(chan)) {
bytes_allowed = comm_get_txspace(chan);
}
count = bytes_allowed / (MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES);
2011-09-08 22:29:39 -03:00
2012-09-19 18:29:23 -03:00
while (_queued_parameter != NULL && count--) {
AP_Param *vp;
float value;
2011-09-08 22:29:39 -03:00
2012-09-19 18:29:23 -03:00
// copy the current parameter and prepare to move to the next
vp = _queued_parameter;
2011-09-08 22:29:39 -03:00
2012-09-19 18:29:23 -03:00
// if the parameter can be cast to float, report it here and break out of the loop
value = vp->cast_to_float(_queued_parameter_type);
2011-09-08 22:29:39 -03:00
2012-11-20 06:36:13 -04:00
char param_name[AP_MAX_NAME_SIZE];
2013-04-19 04:53:52 -03:00
vp->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);
2012-09-19 18:29:23 -03:00
mavlink_msg_param_value_send(
chan,
param_name,
value,
mav_var_type(_queued_parameter_type),
_queued_parameter_count,
_queued_parameter_index);
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type);
_queued_parameter_index++;
}
_queued_parameter_send_time_ms = tnow;
2011-09-18 03:39:09 -03:00
}
2011-09-08 22:29:39 -03:00
2011-09-18 03:39:09 -03:00
/**
2012-08-21 23:19:51 -03:00
* @brief Send the next pending waypoint, called from deferred message
* handling code
*/
2011-09-18 03:39:09 -03:00
void
GCS_MAVLINK::queued_waypoint_send()
{
2011-09-08 22:29:39 -03:00
if (waypoint_receiving &&
2012-08-09 03:20:13 -03:00
waypoint_request_i <= waypoint_request_last) {
2012-08-08 23:22:46 -03:00
mavlink_msg_mission_request_send(
2011-09-08 22:29:39 -03:00
chan,
waypoint_dest_sysid,
waypoint_dest_compid,
waypoint_request_i);
}
}
2012-12-04 18:22:21 -04:00
void GCS_MAVLINK::reset_cli_timeout() {
_cli_timeout = millis();
}
2011-09-08 22:29:39 -03:00
/*
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;
2012-12-04 18:22:21 -04:00
if (!gcs0.initialised) 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)
{
2011-09-18 01:00:49 -03:00
gcs0.send_message(id);
2011-11-20 05:31:45 -04:00
if (gcs3.initialised) {
gcs3.send_message(id);
}
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
{
2012-04-01 20:24:05 -03:00
gcs0.data_stream_send();
2011-11-20 05:31:45 -04:00
if (gcs3.initialised) {
2012-04-01 20:24:05 -03:00
gcs3.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)
{
2012-08-21 23:19:51 -03:00
gcs0.update();
2011-11-20 05:31:45 -04:00
if (gcs3.initialised) {
gcs3.update();
}
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
{
2012-12-12 17:59:31 -04:00
gcs0.send_text_P(severity, str);
2011-11-20 05:31:45 -04:00
if (gcs3.initialised) {
2012-12-12 17:59:31 -04:00
gcs3.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;
2012-09-24 04:39:09 -03:00
gcs0.pending_status.severity = (uint8_t)SEVERITY_LOW;
2012-11-12 00:30:04 -04:00
va_start(arg_list, fmt);
2012-12-18 21:37:56 -04:00
hal.util->vsnprintf_P((char *)gcs0.pending_status.text,
sizeof(gcs0.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-05-02 22:16:50 -03:00
DataFlash.Log_Write_Message(gcs0.pending_status.text);
2013-05-02 23:40:35 -03:00
#endif
2012-09-24 04:39:09 -03:00
gcs3.pending_status = gcs0.pending_status;
2011-09-18 05:57:41 -03:00
mavlink_send_message(MAVLINK_COMM_0, MSG_STATUSTEXT, 0);
2011-12-03 18:06:08 -04:00
if (gcs3.initialised) {
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
}
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)
{
if (comm_get_txspace(MAVLINK_COMM_0) - MAVLINK_NUM_NON_PAYLOAD_BYTES >=
MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN) {
airspeed.log_mavlink_send(MAVLINK_COMM_0, vg);
}
if (gcs3.initialised) {
if (comm_get_txspace(MAVLINK_COMM_1) - MAVLINK_NUM_NON_PAYLOAD_BYTES >=
MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN) {
airspeed.log_mavlink_send(MAVLINK_COMM_1, vg);
}
}
}