2011-09-08 22:29:39 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-13 03:09:36 -03:00
# include "Plane.h"
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
2015-05-13 03:09:36 -03:00
void Plane : : send_heartbeat ( mavlink_channel_t chan )
2011-09-18 03:39:09 -03:00
{
2011-10-29 22:41:32 -03:00
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED ;
2015-07-29 18:44:44 -03:00
uint8_t system_status ;
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 ;
2015-08-20 17:44:32 -03:00
} else if ( plane . crash_state . is_crashed ) {
2015-07-29 18:44:44 -03:00
system_status = MAV_STATE_EMERGENCY ;
} else if ( is_flying ( ) ) {
system_status = MAV_STATE_ACTIVE ;
} else {
system_status = MAV_STATE_STANDBY ;
2013-02-08 22:11:26 -04:00
}
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 ;
}
2015-07-13 03:07:40 -03:00
# if HIL_SUPPORT
2015-03-13 08:33:48 -03:00
if ( g . hil_mode = = 1 ) {
base_mode | = MAV_MODE_FLAG_HIL_ENABLED ;
}
2015-07-13 03:07:40 -03:00
# endif
2011-10-16 04:01:14 -03:00
// we are armed if we are not initialising
2015-01-28 19:30:00 -04:00
if ( control_mode ! = INITIALISING & & hal . util - > get_soft_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
}
2015-05-13 03:09:36 -03:00
void Plane : : send_attitude ( mavlink_channel_t chan )
2011-09-18 03:39:09 -03:00
{
2015-05-22 19:57:00 -03:00
const Vector3f & omega = ahrs . get_gyro ( ) ;
2011-09-18 03:39:09 -03:00
mavlink_msg_attitude_send (
chan ,
2015-05-13 19:05:32 -03:00
millis ( ) ,
2012-03-11 05:13:31 -03:00
ahrs . roll ,
2015-04-11 06:43:13 -03:00
ahrs . pitch - radians ( g . pitch_trim_cd * 0.01f ) ,
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
2015-05-13 03:09:36 -03:00
void Plane : : send_fence_status ( mavlink_channel_t chan )
2011-12-15 21:41:11 -04:00
{
geofence_send_status ( chan ) ;
}
# endif
2015-05-13 03:09:36 -03:00
void Plane : : 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-12-07 22:48:32 -04:00
# if OPTFLOW == ENABLED
if ( optflow . enabled ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW ;
}
# endif
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
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
2011-10-16 04:01:14 -03:00
break ;
case INITIALISING :
break ;
}
2014-09-14 05:37:52 -03:00
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
if ( hal . util - > safety_switch_state ( ) ! = AP_HAL : : Util : : SAFETY_DISARMED ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS ;
}
2014-08-13 02:00:19 -03:00
// default: all present sensors healthy except baro, 3D_MAG, GPS, DIFFERNTIAL_PRESSURE. GEOFENCE always defaults to healthy.
control_sensors_health = control_sensors_present & ~ ( MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE |
MAV_SYS_STATUS_SENSOR_3D_MAG |
2013-10-29 19:03:20 -03:00
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-10-02 01:45:10 -03:00
if ( ahrs . initialised ( ) & & ! ahrs . healthy ( ) ) {
2014-05-15 07:53:18 -03:00
// AHRS subsystem is unhealthy
control_sensors_health & = ~ MAV_SYS_STATUS_AHRS ;
}
2015-05-12 03:19:15 -03:00
if ( ahrs . have_inertial_nav ( ) & & ! ins . accel_calibrated_ok_all ( ) ) {
2015-01-02 02:39:08 -04:00
// trying to use EKF without properly calibrated accelerometers
control_sensors_health & = ~ MAV_SYS_STATUS_AHRS ;
}
2015-01-06 21:45:19 -04:00
if ( barometer . all_healthy ( ) ) {
2014-08-13 02:00:19 -03:00
control_sensors_health | = MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE ;
}
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
}
2014-12-07 22:48:32 -04:00
# if OPTFLOW == ENABLED
if ( optflow . healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW ;
}
# endif
2015-09-17 09:32:06 -03:00
if ( ! ins . get_gyro_health_all ( ) | | ! ins . gyro_calibrated_ok_all ( ) ) {
2014-09-01 08:22:29 -03:00
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_3D_GYRO ;
}
if ( ! ins . get_accel_health_all ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_3D_ACCEL ;
2013-10-29 19:03:20 -03:00
}
if ( airspeed . healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ;
}
2015-06-20 01:52:42 -03:00
# if GEOFENCE_ENABLED
2014-02-13 18:49:42 -04:00
if ( geofence_breached ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_GEOFENCE ;
}
2015-06-20 01:52:42 -03:00
# endif
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
2015-03-18 08:11:52 -03:00
if ( battery . has_current ( ) & & battery . healthy ( ) ) {
2013-09-29 09:54:39 -03:00
battery_remaining = battery . capacity_remaining_pct ( ) ;
battery_current = battery . current_amps ( ) * 100 ;
2011-10-16 04:01:14 -03:00
}
2014-07-24 18:58:39 -03:00
# if AP_TERRAIN_AVAILABLE
2014-07-24 07:16:18 -03:00
switch ( terrain . status ( ) ) {
case AP_Terrain : : TerrainStatusDisabled :
break ;
case AP_Terrain : : TerrainStatusUnhealthy :
control_sensors_present | = MAV_SYS_STATUS_TERRAIN ;
control_sensors_enabled | = MAV_SYS_STATUS_TERRAIN ;
break ;
case AP_Terrain : : TerrainStatusOK :
control_sensors_present | = MAV_SYS_STATUS_TERRAIN ;
control_sensors_enabled | = MAV_SYS_STATUS_TERRAIN ;
control_sensors_health | = MAV_SYS_STATUS_TERRAIN ;
break ;
}
# endif
2015-05-13 20:00:11 -03:00
# if RANGEFINDER_ENABLED == ENABLED
2014-11-14 00:34:36 -04:00
if ( rangefinder . num_sensors ( ) > 0 ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
if ( g . rangefinder_landing ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
}
2015-04-17 03:37:00 -03:00
if ( rangefinder . has_data ( ) ) {
2014-11-14 00:34:36 -04:00
control_sensors_health | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
}
}
2015-05-13 20:00:11 -03:00
# endif
2014-11-14 00:34:36 -04:00
2015-03-08 18:25:33 -03:00
if ( AP_Notify : : flags . initialising ) {
// while initialising the gyros and accels are not enabled
control_sensors_enabled & = ~ ( MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL ) ;
control_sensors_health & = ~ ( MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL ) ;
}
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
}
2015-05-13 03:09:36 -03:00
void Plane : : send_location ( mavlink_channel_t chan )
2011-09-18 03:39:09 -03:00
{
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 {
2015-05-13 19:05:32 -03:00
fix_time_ms = 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
2015-09-07 08:10:20 -03:00
current_loc . alt * 10UL , // millimeters above sea level
2014-07-08 07:26:07 -03:00
relative_altitude ( ) * 1.0e3 f , // 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
}
2015-05-13 03:09:36 -03:00
void Plane : : send_nav_controller_output ( mavlink_channel_t chan )
2011-09-18 03:39:09 -03:00
{
mavlink_msg_nav_controller_output_send (
chan ,
2015-04-11 06:43:13 -03:00
nav_roll_cd * 0.01f ,
nav_pitch_cd * 0.01f ,
2013-04-11 21:25:46 -03:00
nav_controller - > nav_bearing_cd ( ) * 0.01f ,
nav_controller - > target_bearing_cd ( ) * 0.01f ,
2015-01-01 00:17:45 -04:00
auto_state . wp_distance ,
2015-04-11 06:43:13 -03:00
altitude_error_cm * 0.01f ,
2012-08-07 03:05:51 -03:00
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
2015-05-13 03:09:36 -03:00
void Plane : : 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 ,
2015-05-13 19:05:32 -03:00
millis ( ) ,
2011-10-16 04:01:14 -03:00
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
}
2015-05-13 03:09:36 -03:00
void Plane : : send_radio_out ( mavlink_channel_t chan )
2011-09-18 03:39:09 -03:00
{
2015-07-13 03:07:40 -03:00
# if HIL_SUPPORT
2015-03-13 08:33:48 -03:00
if ( g . hil_mode = = 1 & & ! g . hil_servos ) {
2013-03-30 00:38:43 -03:00
mavlink_msg_servo_output_raw_send (
chan ,
2015-05-13 19:05:32 -03:00
micros ( ) ,
2013-03-30 00:38:43 -03:00
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 ;
}
2015-07-13 03:07:40 -03:00
# endif
2012-08-21 23:19:51 -03:00
mavlink_msg_servo_output_raw_send (
chan ,
2015-05-13 19:05:32 -03:00
micros ( ) ,
2012-08-21 23:19:51 -03:00
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
}
2015-05-13 03:09:36 -03:00
void Plane : : send_vfr_hud ( mavlink_channel_t chan )
2011-09-18 03:39:09 -03:00
{
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 ;
}
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 ,
2014-08-03 04:16:51 -03:00
throttle_percentage ( ) ,
2015-04-11 06:43:13 -03:00
current_loc . alt / 100.0f ,
2012-07-04 22:11:07 -03:00
barometer . get_climb_rate ( ) ) ;
2011-09-18 03:39:09 -03:00
}
2013-11-22 19:47:34 -04:00
/*
keep last HIL_STATE message to allow sending SIM_STATE
*/
2015-07-13 03:07:40 -03:00
# if HIL_SUPPORT
2013-11-22 19:47:34 -04:00
static mavlink_hil_state_t last_hil_state ;
2015-07-13 03:07:40 -03:00
# endif
2013-11-22 19:47:34 -04:00
2012-03-01 00:23:00 -04:00
// report simulator state
2015-05-13 03:09:36 -03:00
void Plane : : send_simstate ( mavlink_channel_t chan )
2012-03-01 00:23:00 -04:00
{
2015-05-04 03:18:55 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2012-06-29 02:10:35 -03:00
sitl . simstate_send ( chan ) ;
2015-07-13 03:07:40 -03:00
# elif HIL_SUPPORT
2015-03-13 08:33:48 -03:00
if ( g . hil_mode = = 1 ) {
mavlink_msg_simstate_send ( chan ,
last_hil_state . roll ,
last_hil_state . pitch ,
last_hil_state . yaw ,
last_hil_state . xacc * 0.001f * GRAVITY_MSS ,
last_hil_state . yacc * 0.001f * GRAVITY_MSS ,
last_hil_state . zacc * 0.001f * 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
2015-05-13 03:09:36 -03:00
void Plane : : send_hwstatus ( mavlink_channel_t chan )
2012-03-01 00:23:00 -04:00
{
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
2015-05-13 03:09:36 -03:00
void Plane : : send_wind ( mavlink_channel_t chan )
2012-08-11 02:57:13 -03:00
{
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 ) ;
}
2015-05-22 19:57:00 -03:00
/*
send PID tuning message
*/
void Plane : : send_pid_tuning ( mavlink_channel_t chan )
{
const Vector3f & gyro = ahrs . get_gyro ( ) ;
if ( g . gcs_pid_mask & 1 ) {
const DataFlash_Class : : PID_Info & pid_info = rollController . get_pid_info ( ) ;
2015-06-08 08:08:34 -03:00
mavlink_msg_pid_tuning_send ( chan , PID_TUNING_ROLL ,
2015-05-22 19:57:00 -03:00
pid_info . desired ,
degrees ( gyro . x ) ,
pid_info . FF ,
pid_info . P ,
pid_info . I ,
pid_info . D ) ;
if ( ! HAVE_PAYLOAD_SPACE ( chan , PID_TUNING ) ) {
return ;
}
}
if ( g . gcs_pid_mask & 2 ) {
const DataFlash_Class : : PID_Info & pid_info = pitchController . get_pid_info ( ) ;
2015-06-08 08:08:34 -03:00
mavlink_msg_pid_tuning_send ( chan , PID_TUNING_PITCH ,
2015-05-22 19:57:00 -03:00
pid_info . desired ,
degrees ( gyro . y ) ,
pid_info . FF ,
pid_info . P ,
pid_info . I ,
pid_info . D ) ;
if ( ! HAVE_PAYLOAD_SPACE ( chan , PID_TUNING ) ) {
return ;
}
}
2015-06-22 00:27:40 -03:00
if ( g . gcs_pid_mask & 4 ) {
const DataFlash_Class : : PID_Info & pid_info = yawController . get_pid_info ( ) ;
mavlink_msg_pid_tuning_send ( chan , PID_TUNING_YAW ,
pid_info . desired ,
degrees ( gyro . z ) ,
pid_info . FF ,
pid_info . P ,
pid_info . I ,
pid_info . D ) ;
if ( ! HAVE_PAYLOAD_SPACE ( chan , PID_TUNING ) ) {
return ;
}
}
2015-06-08 08:08:34 -03:00
if ( g . gcs_pid_mask & 8 ) {
const DataFlash_Class : : PID_Info & pid_info = steerController . get_pid_info ( ) ;
mavlink_msg_pid_tuning_send ( chan , PID_TUNING_STEER ,
pid_info . desired ,
degrees ( gyro . z ) ,
pid_info . FF ,
pid_info . P ,
pid_info . I ,
pid_info . D ) ;
if ( ! HAVE_PAYLOAD_SPACE ( chan , PID_TUNING ) ) {
return ;
}
}
2015-05-22 19:57:00 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : send_rangefinder ( mavlink_channel_t chan )
2013-10-30 19:54:45 -03:00
{
2015-05-13 20:00:11 -03:00
# if RANGEFINDER_ENABLED == ENABLED
2015-04-17 03:37:00 -03:00
if ( ! rangefinder . has_data ( ) ) {
2013-10-30 19:54:45 -03:00
// no sonar to report
return ;
}
mavlink_msg_rangefinder_send (
chan ,
2014-08-26 08:17:47 -03:00
rangefinder . distance_cm ( ) * 0.01f ,
rangefinder . voltage_mv ( ) * 0.001f ) ;
2015-05-13 20:00:11 -03:00
# endif
2013-10-30 19:54:45 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : send_current_waypoint ( mavlink_channel_t chan )
2011-09-18 03:39:09 -03:00
{
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
}
2015-05-13 03:09:36 -03:00
void Plane : : send_statustext ( mavlink_channel_t chan )
2011-09-18 05:57:41 -03:00
{
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?
2015-05-13 03:09:36 -03:00
bool Plane : : telemetry_delayed ( mavlink_channel_t chan )
2012-08-29 19:59:39 -03:00
{
2015-05-13 19:05:32 -03:00
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 ;
}
2014-07-26 03:58:13 -03:00
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
{
2015-05-13 03:09:36 -03:00
if ( plane . 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
2015-05-13 03:09:36 -03:00
if ( ! plane . in_mavlink_delay & & plane . scheduler . time_available_usec ( ) < 1200 ) {
plane . gcs_out_of_time = true ;
2013-07-05 05:05:27 -03:00
return false ;
}
2011-09-18 03:39:09 -03:00
switch ( id ) {
case MSG_HEARTBEAT :
CHECK_PAYLOAD_SIZE ( HEARTBEAT ) ;
2015-05-13 19:05:32 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . last_heartbeat_time = plane . millis ( ) ;
2015-05-13 03:09:36 -03:00
plane . send_heartbeat ( chan ) ;
2011-09-18 03:39:09 -03:00
return true ;
case MSG_EXTENDED_STATUS1 :
CHECK_PAYLOAD_SIZE ( SYS_STATUS ) ;
2015-05-13 03:09:36 -03:00
plane . send_extended_status1 ( chan ) ;
2015-06-20 00:26:34 -03:00
CHECK_PAYLOAD_SIZE2 ( POWER_STATUS ) ;
2015-05-13 03:09:36 -03:00
plane . 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 ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_meminfo ( ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_ATTITUDE :
CHECK_PAYLOAD_SIZE ( ATTITUDE ) ;
2015-05-13 03:09:36 -03:00
plane . send_attitude ( chan ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_LOCATION :
CHECK_PAYLOAD_SIZE ( GLOBAL_POSITION_INT ) ;
2015-05-13 03:09:36 -03:00
plane . send_location ( chan ) ;
2011-09-18 03:39:09 -03:00
break ;
2015-04-05 13:25:41 -03:00
case MSG_LOCAL_POSITION :
CHECK_PAYLOAD_SIZE ( LOCAL_POSITION_NED ) ;
2015-05-13 03:09:36 -03:00
send_local_position ( plane . ahrs ) ;
2015-04-05 13:25:41 -03:00
break ;
2011-09-18 03:39:09 -03:00
case MSG_NAV_CONTROLLER_OUTPUT :
2015-05-13 03:09:36 -03:00
if ( plane . control_mode ! = MANUAL ) {
2011-09-18 03:39:09 -03:00
CHECK_PAYLOAD_SIZE ( NAV_CONTROLLER_OUTPUT ) ;
2015-05-13 03:09:36 -03:00
plane . send_nav_controller_output ( chan ) ;
2011-09-18 03:39:09 -03:00
}
break ;
case MSG_GPS_RAW :
2011-10-16 04:01:14 -03:00
CHECK_PAYLOAD_SIZE ( GPS_RAW_INT ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_gps_raw ( plane . 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 ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_system_time ( plane . gps ) ;
2013-10-23 08:15:06 -03:00
break ;
2011-09-18 03:39:09 -03:00
case MSG_SERVO_OUT :
2015-07-13 03:07:40 -03:00
# if HIL_SUPPORT
2015-05-13 03:09:36 -03:00
if ( plane . g . hil_mode = = 1 ) {
2015-03-13 08:33:48 -03:00
CHECK_PAYLOAD_SIZE ( RC_CHANNELS_SCALED ) ;
2015-05-13 03:09:36 -03:00
plane . send_servo_out ( chan ) ;
2015-03-13 08:33:48 -03:00
}
2015-07-13 03:07:40 -03:00
# endif
2011-09-18 03:39:09 -03:00
break ;
case MSG_RADIO_IN :
CHECK_PAYLOAD_SIZE ( RC_CHANNELS_RAW ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_radio_in ( plane . receiver_rssi ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_RADIO_OUT :
CHECK_PAYLOAD_SIZE ( SERVO_OUTPUT_RAW ) ;
2015-05-13 03:09:36 -03:00
plane . send_radio_out ( chan ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_VFR_HUD :
CHECK_PAYLOAD_SIZE ( VFR_HUD ) ;
2015-05-13 03:09:36 -03:00
plane . send_vfr_hud ( chan ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_RAW_IMU1 :
CHECK_PAYLOAD_SIZE ( RAW_IMU ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_raw_imu ( plane . ins , plane . compass ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_RAW_IMU2 :
CHECK_PAYLOAD_SIZE ( SCALED_PRESSURE ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_scaled_pressure ( plane . barometer ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_RAW_IMU3 :
CHECK_PAYLOAD_SIZE ( SENSOR_OFFSETS ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_sensor_offsets ( plane . ins , plane . compass , plane . barometer ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_CURRENT_WAYPOINT :
2012-08-08 23:22:46 -03:00
CHECK_PAYLOAD_SIZE ( MISSION_CURRENT ) ;
2015-05-13 03:09:36 -03:00
plane . send_current_waypoint ( chan ) ;
2011-09-18 03:39:09 -03:00
break ;
case MSG_NEXT_PARAM :
CHECK_PAYLOAD_SIZE ( PARAM_VALUE ) ;
2015-05-13 03:09:36 -03:00
plane . 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 ) ;
2015-05-13 03:09:36 -03:00
plane . 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 ) ;
2015-05-13 03:09:36 -03:00
plane . send_statustext ( chan ) ;
2011-09-18 05:57:41 -03:00
break ;
2011-12-15 21:41:11 -04:00
# if GEOFENCE_ENABLED == ENABLED
case MSG_FENCE_STATUS :
CHECK_PAYLOAD_SIZE ( FENCE_STATUS ) ;
2015-05-13 03:09:36 -03:00
plane . send_fence_status ( chan ) ;
2011-12-15 21:41:11 -04:00
break ;
# endif
2012-03-11 05:13:31 -03:00
case MSG_AHRS :
CHECK_PAYLOAD_SIZE ( AHRS ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_ahrs ( plane . ahrs ) ;
2012-03-01 00:23:00 -04:00
break ;
case MSG_SIMSTATE :
2012-03-11 05:13:31 -03:00
CHECK_PAYLOAD_SIZE ( SIMSTATE ) ;
2015-05-13 03:09:36 -03:00
plane . send_simstate ( chan ) ;
2015-06-20 00:26:34 -03:00
CHECK_PAYLOAD_SIZE2 ( AHRS2 ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_ahrs2 ( plane . ahrs ) ;
2012-03-01 00:23:00 -04:00
break ;
case MSG_HWSTATUS :
CHECK_PAYLOAD_SIZE ( HWSTATUS ) ;
2015-05-13 03:09:36 -03:00
plane . send_hwstatus ( chan ) ;
2012-03-01 00:23:00 -04:00
break ;
2013-10-30 19:54:45 -03:00
case MSG_RANGEFINDER :
CHECK_PAYLOAD_SIZE ( RANGEFINDER ) ;
2015-05-13 03:09:36 -03:00
plane . send_rangefinder ( chan ) ;
2013-10-30 19:54:45 -03:00
break ;
2014-07-21 19:24:00 -03:00
case MSG_TERRAIN :
2014-07-24 18:58:39 -03:00
# if AP_TERRAIN_AVAILABLE
2014-07-21 19:24:00 -03:00
CHECK_PAYLOAD_SIZE ( TERRAIN_REQUEST ) ;
2015-05-13 03:09:36 -03:00
plane . terrain . send_request ( chan ) ;
2014-07-21 19:24:00 -03:00
# endif
break ;
2014-11-10 21:27:59 -04:00
case MSG_CAMERA_FEEDBACK :
# if CAMERA == ENABLED
CHECK_PAYLOAD_SIZE ( CAMERA_FEEDBACK ) ;
2015-05-13 03:09:36 -03:00
plane . camera . send_feedback ( chan , plane . gps , plane . ahrs , plane . current_loc ) ;
2014-11-10 21:27:59 -04:00
# endif
break ;
2014-08-08 23:14:21 -03:00
case MSG_BATTERY2 :
CHECK_PAYLOAD_SIZE ( BATTERY2 ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_battery2 ( plane . battery ) ;
2014-08-08 23:14:21 -03:00
break ;
2012-08-11 02:57:13 -03:00
case MSG_WIND :
CHECK_PAYLOAD_SIZE ( WIND ) ;
2015-05-13 03:09:36 -03:00
plane . send_wind ( chan ) ;
2012-08-11 02:57:13 -03:00
break ;
2014-11-17 19:52:01 -04:00
case MSG_MOUNT_STATUS :
# if MOUNT == ENABLED
CHECK_PAYLOAD_SIZE ( MOUNT_STATUS ) ;
2015-05-13 03:09:36 -03:00
plane . camera_mount . status_msg ( chan ) ;
2014-11-17 19:52:01 -04:00
# endif // MOUNT == ENABLED
break ;
2014-12-08 01:07:49 -04:00
case MSG_OPTICAL_FLOW :
# if OPTFLOW == ENABLED
CHECK_PAYLOAD_SIZE ( OPTICAL_FLOW ) ;
2015-05-13 03:09:36 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_opticalflow ( plane . ahrs , plane . optflow ) ;
2014-12-08 01:07:49 -04:00
# endif
break ;
2015-03-12 00:31:24 -03:00
case MSG_EKF_STATUS_REPORT :
# if AP_AHRS_NAVEKF_AVAILABLE
CHECK_PAYLOAD_SIZE ( EKF_STATUS_REPORT ) ;
2015-05-13 03:09:36 -03:00
plane . ahrs . get_NavEKF ( ) . send_status_report ( chan ) ;
2015-03-12 00:31:24 -03:00
# endif
break ;
2015-05-25 19:30:30 -03:00
case MSG_GIMBAL_REPORT :
# if MOUNT == ENABLED
CHECK_PAYLOAD_SIZE ( GIMBAL_REPORT ) ;
plane . camera_mount . send_gimbal_report ( chan ) ;
# endif
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 ;
2015-05-22 19:57:00 -03:00
case MSG_PID_TUNING :
CHECK_PAYLOAD_SIZE ( PID_TUNING ) ;
plane . send_pid_tuning ( chan ) ;
break ;
2015-06-12 04:00:06 -03:00
case MSG_VIBRATION :
CHECK_PAYLOAD_SIZE ( VIBRATION ) ;
send_vibration ( plane . ins ) ;
break ;
2015-08-10 01:28:00 -03:00
case MSG_RPM :
// unused
break ;
2015-07-20 03:11:34 -03:00
case MSG_MISSION_ITEM_REACHED :
CHECK_PAYLOAD_SIZE ( MISSION_ITEM_REACHED ) ;
mavlink_msg_mission_item_reached_send ( chan , mission_item_reached_index ) ;
break ;
2015-07-31 00:21:50 -03:00
case MSG_MAG_CAL_PROGRESS :
CHECK_PAYLOAD_SIZE ( MAG_CAL_PROGRESS ) ;
plane . compass . send_mag_cal_progress ( chan ) ;
break ;
case MSG_MAG_CAL_REPORT :
CHECK_PAYLOAD_SIZE ( MAG_CAL_REPORT ) ;
plane . compass . send_mag_cal_report ( chan ) ;
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 1 Hz
*/
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 ) ) {
2014-07-08 07:26:07 -03:00
rate * = 0.25f ;
2012-08-15 21:50:12 -03:00
}
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 ;
}
2015-02-19 08:50:10 -04:00
stream_ticks [ stream_num ] = ( 50 / rate ) - 1 + 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
{
2015-05-13 03:09:36 -03:00
plane . gcs_out_of_time = false ;
2013-07-05 05:05:27 -03:00
2015-05-13 03:09:36 -03:00
if ( ! plane . in_mavlink_delay ) {
handle_log_send ( plane . DataFlash ) ;
2013-12-15 03:59:23 -04:00
}
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
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
2015-05-13 03:09:36 -03:00
if ( plane . in_mavlink_delay ) {
2015-07-13 03:07:40 -03:00
# if HIL_SUPPORT
2015-05-13 03:09:36 -03:00
if ( plane . g . hil_mode = = 1 ) {
2015-03-13 08:33:48 -03:00
// 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 ) ;
}
2012-12-03 08:26:39 -04:00
}
2015-07-13 03:07:40 -03:00
# endif
2012-05-22 03:13:23 -03:00
// don't send any other stream types while in the delay callback
return ;
}
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
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
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
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
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
2012-04-01 20:24:05 -03:00
if ( stream_trigger ( STREAM_POSITION ) ) {
// sent with GPS read
send_message ( MSG_LOCATION ) ;
2015-04-05 13:25:41 -03:00
send_message ( MSG_LOCAL_POSITION ) ;
2012-04-01 20:24:05 -03:00
}
2011-09-08 22:29:39 -03:00
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
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
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
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
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
2012-04-01 20:24:05 -03:00
if ( stream_trigger ( STREAM_EXTRA1 ) ) {
send_message ( MSG_ATTITUDE ) ;
send_message ( MSG_SIMSTATE ) ;
2015-05-22 19:57:00 -03:00
if ( plane . control_mode ! = MANUAL ) {
send_message ( MSG_PID_TUNING ) ;
}
2012-04-01 20:24:05 -03:00
}
2011-09-08 22:29:39 -03:00
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
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
2015-05-13 03:09:36 -03:00
if ( plane . gcs_out_of_time ) return ;
2013-07-05 05:05:27 -03:00
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 ) ;
2014-07-24 18:58:39 -03:00
# if AP_TERRAIN_AVAILABLE
2014-07-21 19:24:00 -03:00
send_message ( MSG_TERRAIN ) ;
# endif
2015-07-31 00:21:50 -03:00
send_message ( MSG_MAG_CAL_REPORT ) ;
send_message ( MSG_MAG_CAL_PROGRESS ) ;
2014-08-08 23:14:21 -03:00
send_message ( MSG_BATTERY2 ) ;
2014-11-17 19:52:01 -04:00
send_message ( MSG_MOUNT_STATUS ) ;
2014-12-08 01:07:49 -04:00
send_message ( MSG_OPTICAL_FLOW ) ;
2015-03-12 00:31:24 -03:00
send_message ( MSG_EKF_STATUS_REPORT ) ;
2015-05-25 19:30:30 -03:00
send_message ( MSG_GIMBAL_REPORT ) ;
2015-06-12 04:00:06 -03:00
send_message ( MSG_VIBRATION ) ;
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
{
2015-05-13 03:09:36 -03:00
if ( plane . control_mode ! = GUIDED ) {
2015-05-10 01:28:02 -03:00
// only accept position updates when in GUIDED mode
return ;
}
2015-05-13 03:09:36 -03:00
plane . guided_WP_loc = cmd . content . location ;
2014-03-18 19:59:51 -03:00
// add home alt if needed
2015-05-13 03:09:36 -03:00
if ( plane . guided_WP_loc . flags . relative_alt ) {
plane . guided_WP_loc . alt + = plane . home . alt ;
plane . guided_WP_loc . flags . relative_alt = 0 ;
2014-03-18 19:59:51 -03:00
}
2011-09-08 22:29:39 -03:00
2015-05-13 03:09:36 -03:00
plane . set_guided_WP ( ) ;
2014-03-18 19:59:51 -03:00
}
/*
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 )
{
2015-05-13 03:09:36 -03:00
plane . next_WP_loc . alt = cmd . content . location . alt ;
2014-03-18 19:59:51 -03:00
if ( cmd . content . location . flags . relative_alt ) {
2015-05-13 03:09:36 -03:00
plane . next_WP_loc . alt + = plane . home . alt ;
2014-03-18 19:59:51 -03:00
}
2015-05-13 03:09:36 -03:00
plane . next_WP_loc . flags . relative_alt = false ;
plane . next_WP_loc . flags . terrain_alt = cmd . content . location . flags . terrain_alt ;
plane . reset_offset_altitude ( ) ;
2014-03-18 19:59:51 -03:00
}
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 ) ;
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
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " command received: " ) ) ;
2012-08-21 23:19:51 -03:00
switch ( packet . command ) {
2015-06-10 03:46:17 -03:00
case MAV_CMD_START_RX_PAIR :
// initiate bind procedure
if ( ! hal . rcin - > rc_bind ( packet . param1 ) ) {
result = MAV_RESULT_FAILED ;
} else {
result = MAV_RESULT_ACCEPTED ;
}
break ;
2012-08-21 23:19:51 -03:00
case MAV_CMD_NAV_LOITER_UNLIM :
2015-05-13 03:09:36 -03:00
plane . set_mode ( LOITER ) ;
2012-08-21 23:19:51 -03:00
result = MAV_RESULT_ACCEPTED ;
break ;
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
2015-05-13 03:09:36 -03:00
plane . set_mode ( RTL ) ;
2012-08-21 23:19:51 -03:00
result = MAV_RESULT_ACCEPTED ;
break ;
2014-07-04 03:54:31 -03:00
# if MOUNT == ENABLED
// Sets the region of interest (ROI) for the camera
case MAV_CMD_DO_SET_ROI :
2015-08-27 02:40:14 -03:00
// sanity check location
if ( fabsf ( packet . param5 ) > 90.0f | | fabsf ( packet . param6 ) > 180.0f ) {
break ;
}
2014-07-04 03:54:31 -03:00
Location roi_loc ;
roi_loc . lat = ( int32_t ) ( packet . param5 * 1.0e7 f ) ;
roi_loc . lng = ( int32_t ) ( packet . param6 * 1.0e7 f ) ;
roi_loc . alt = ( int32_t ) ( packet . param7 * 100.0f ) ;
if ( roi_loc . lat = = 0 & & roi_loc . lng = = 0 & & roi_loc . alt = = 0 ) {
// switch off the camera tracking if enabled
2015-05-13 03:09:36 -03:00
if ( plane . camera_mount . get_mode ( ) = = MAV_MOUNT_MODE_GPS_POINT ) {
plane . camera_mount . set_mode_to_default ( ) ;
2014-07-04 03:54:31 -03:00
}
} else {
// send the command to the camera mount
2015-05-13 03:09:36 -03:00
plane . camera_mount . set_roi_target ( roi_loc ) ;
2014-07-04 03:54:31 -03:00
}
result = MAV_RESULT_ACCEPTED ;
break ;
# endif
2015-09-06 17:44:33 -03:00
# if CAMERA == ENABLED
case MAV_CMD_DO_DIGICAM_CONFIGURE :
plane . camera . configure ( packet . param1 ,
packet . param2 ,
packet . param3 ,
packet . param4 ,
packet . param5 ,
packet . param6 ,
packet . param7 ) ;
result = MAV_RESULT_ACCEPTED ;
break ;
case MAV_CMD_DO_DIGICAM_CONTROL :
plane . camera . control ( packet . param1 ,
packet . param2 ,
packet . param3 ,
packet . param4 ,
packet . param5 ,
packet . param6 ) ;
result = MAV_RESULT_ACCEPTED ;
break ;
# endif // CAMERA == ENABLED
2015-09-02 04:47:20 -03:00
case MAV_CMD_DO_MOUNT_CONTROL :
# if MOUNT == ENABLED
plane . camera_mount . control ( packet . param1 , packet . param2 , packet . param3 , ( MAV_MOUNT_MODE ) packet . param7 ) ;
# endif
break ;
2012-08-21 23:19:51 -03:00
case MAV_CMD_MISSION_START :
2015-05-13 03:09:36 -03:00
plane . set_mode ( AUTO ) ;
2012-08-21 23:19:51 -03:00
result = MAV_RESULT_ACCEPTED ;
break ;
case MAV_CMD_PREFLIGHT_CALIBRATION :
2015-05-13 03:09:36 -03:00
plane . in_calibration = true ;
2015-05-04 23:34:27 -03:00
if ( is_equal ( packet . param1 , 1.0f ) ) {
2015-05-13 03:09:36 -03:00
plane . ins . init_gyro ( ) ;
if ( plane . ins . gyro_calibrated_ok_all ( ) ) {
plane . ahrs . reset_gyro_drift ( ) ;
2015-03-10 20:16:59 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
}
2015-05-04 23:34:27 -03:00
} else if ( is_equal ( packet . param3 , 1.0f ) ) {
2015-05-13 03:09:36 -03:00
plane . init_barometer ( ) ;
if ( plane . airspeed . enabled ( ) ) {
plane . zero_airspeed ( false ) ;
2012-08-21 23:19:51 -03:00
}
2015-03-07 06:31:52 -04:00
result = MAV_RESULT_ACCEPTED ;
2015-05-04 23:34:27 -03:00
} else if ( is_equal ( packet . param4 , 1.0f ) ) {
2015-05-13 03:09:36 -03:00
plane . trim_radio ( ) ;
2015-03-07 06:31:52 -04:00
result = MAV_RESULT_ACCEPTED ;
2015-05-04 23:34:27 -03:00
} else if ( is_equal ( packet . param5 , 1.0f ) ) {
2013-05-08 03:25:35 -03:00
float trim_roll , trim_pitch ;
2015-03-07 06:31:52 -04:00
AP_InertialSensor_UserInteract_MAVLink interact ( this ) ;
2015-09-17 09:32:06 -03:00
// start with gyro calibration
plane . ins . init_gyro ( ) ;
// reset ahrs gyro bias
if ( plane . ins . gyro_calibrated_ok_all ( ) ) {
plane . ahrs . reset_gyro_drift ( ) ;
2014-11-21 04:08:58 -04:00
}
2015-05-13 03:09:36 -03:00
if ( plane . 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
2015-05-13 03:09:36 -03:00
plane . ahrs . set_trim ( Vector3f ( trim_roll , trim_pitch , 0 ) ) ;
2015-03-07 06:31:52 -04:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
2013-05-08 03:25:35 -03:00
}
2015-05-15 18:28:59 -03:00
} else if ( is_equal ( packet . param5 , 2.0f ) ) {
2015-09-17 09:32:06 -03:00
// start with gyro calibration
plane . ins . init_gyro ( ) ;
2015-05-15 18:28:59 -03:00
// accel trim
float trim_roll , trim_pitch ;
2015-05-17 18:35:42 -03:00
if ( plane . ins . calibrate_trim ( trim_roll , trim_pitch ) ) {
2015-05-15 18:28:59 -03:00
// reset ahrs's trim to suggested values from calibration routine
2015-05-17 18:35:42 -03:00
plane . ahrs . set_trim ( Vector3f ( trim_roll , trim_pitch , 0 ) ) ;
2015-05-15 18:28:59 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
}
2013-05-08 03:25:35 -03:00
}
2014-11-20 23:46:42 -04:00
else {
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " Unsupported preflight calibration " ) ) ;
2014-11-20 23:46:42 -04:00
}
2015-05-13 03:09:36 -03:00
plane . in_calibration = false ;
2012-08-21 23:19:51 -03:00
break ;
2011-10-16 04:01:14 -03:00
2014-07-09 05:16:24 -03:00
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS :
2015-05-04 23:34:27 -03:00
if ( is_equal ( packet . param1 , 2.0f ) ) {
2014-07-09 05:16:24 -03:00
// save first compass's offsets
2015-05-13 03:09:36 -03:00
plane . compass . set_and_save_offsets ( 0 , packet . param2 , packet . param3 , packet . param4 ) ;
2014-07-09 05:16:24 -03:00
result = MAV_RESULT_ACCEPTED ;
}
2015-05-04 23:34:27 -03:00
if ( is_equal ( packet . param1 , 5.0f ) ) {
2014-07-09 05:16:24 -03:00
// save secondary compass's offsets
2015-05-13 03:09:36 -03:00
plane . compass . set_and_save_offsets ( 1 , packet . param2 , packet . param3 , packet . param4 ) ;
2014-07-09 05:16:24 -03:00
result = MAV_RESULT_ACCEPTED ;
}
break ;
2013-11-27 22:19:34 -04:00
case MAV_CMD_COMPONENT_ARM_DISARM :
2015-05-04 23:34:27 -03:00
if ( is_equal ( packet . param1 , 1.0f ) ) {
2014-03-19 19:06:48 -03:00
// run pre_arm_checks and arm_checks and display failures
2015-05-13 03:09:36 -03:00
if ( plane . arm_motors ( AP_Arming : : MAVLINK ) ) {
2014-03-19 19:06:48 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
}
2015-05-04 23:34:27 -03:00
} else if ( is_zero ( packet . param1 ) ) {
2015-05-13 03:09:36 -03:00
if ( plane . disarm_motors ( ) ) {
2014-03-19 19:06:48 -03:00
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 :
2015-05-13 03:09:36 -03:00
plane . set_mode ( MANUAL ) ;
2012-08-24 02:18:22 -03:00
result = MAV_RESULT_ACCEPTED ;
break ;
case MAV_MODE_AUTO_ARMED :
case MAV_MODE_AUTO_DISARMED :
2015-05-13 03:09:36 -03:00
plane . set_mode ( AUTO ) ;
2012-08-24 02:18:22 -03:00
result = MAV_RESULT_ACCEPTED ;
break ;
case MAV_MODE_STABILIZE_DISARMED :
case MAV_MODE_STABILIZE_ARMED :
2015-05-13 03:09:36 -03:00
plane . set_mode ( FLY_BY_WIRE_A ) ;
2012-08-24 02:18:22 -03:00
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 :
2015-05-13 03:09:36 -03:00
if ( plane . ServoRelayEvents . do_set_servo ( packet . param1 , packet . param2 ) ) {
2014-01-20 00:36:31 -04:00
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 :
2015-05-13 03:09:36 -03:00
if ( plane . ServoRelayEvents . do_repeat_servo ( packet . param1 , packet . param2 , packet . param3 , packet . param4 * 1000 ) ) {
2014-01-20 00:36:31 -04:00
result = MAV_RESULT_ACCEPTED ;
}
2014-01-19 22:37:33 -04:00
break ;
case MAV_CMD_DO_SET_RELAY :
2015-05-13 03:09:36 -03:00
if ( plane . ServoRelayEvents . do_set_relay ( packet . param1 , packet . param2 ) ) {
2014-01-20 00:36:31 -04:00
result = MAV_RESULT_ACCEPTED ;
}
2014-01-19 22:37:33 -04:00
break ;
case MAV_CMD_DO_REPEAT_RELAY :
2015-05-13 03:09:36 -03:00
if ( plane . ServoRelayEvents . do_repeat_relay ( packet . param1 , packet . param2 , packet . param3 * 1000 ) ) {
2014-01-20 00:36:31 -04:00
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 :
2015-05-04 23:34:27 -03:00
if ( is_equal ( packet . param1 , 1.0f ) | | is_equal ( packet . param1 , 3.0f ) ) {
2013-09-03 22:59:16 -03:00
// when packet.param1 == 3 we reboot to hold in bootloader
2015-05-04 23:34:27 -03:00
hal . scheduler - > reboot ( is_equal ( packet . param1 , 3.0f ) ) ;
2012-09-09 22:42:30 -03:00
result = MAV_RESULT_ACCEPTED ;
}
break ;
2014-10-17 14:35:05 -03:00
case MAV_CMD_DO_LAND_START :
result = MAV_RESULT_FAILED ;
2014-10-24 00:08:20 -03:00
2014-10-17 22:36:49 -03:00
// attempt to switch to next DO_LAND_START command in the mission
2015-05-13 03:09:36 -03:00
if ( plane . jump_to_landing_sequence ( ) ) {
2014-10-17 14:35:05 -03:00
result = MAV_RESULT_ACCEPTED ;
2014-10-24 00:08:20 -03:00
}
2014-10-17 14:35:05 -03:00
break ;
2014-10-21 12:26:33 -03:00
case MAV_CMD_DO_GO_AROUND :
result = MAV_RESULT_FAILED ;
//Not allowing go around at FLIGHT_LAND_FINAL stage on purpose --
//if plane is close to the ground a go around coudld be dangerous.
2015-05-13 03:09:36 -03:00
if ( plane . flight_stage = = AP_SpdHgtControl : : FLIGHT_LAND_APPROACH ) {
2014-10-21 12:26:33 -03:00
//Just tell the autopilot we're done landing so it will
//proceed to the next mission item. If there is no next mission
//item the plane will head to home point and loiter.
2015-05-13 03:09:36 -03:00
plane . auto_state . commanded_go_around = true ;
2014-10-21 12:26:33 -03:00
result = MAV_RESULT_ACCEPTED ;
2015-08-25 18:28:50 -03:00
plane . gcs_send_text_P ( MAV_SEVERITY_CRITICAL , PSTR ( " Go around command accepted. " ) ) ;
2014-10-21 12:26:33 -03:00
} else {
2015-08-25 18:28:50 -03:00
plane . gcs_send_text_P ( MAV_SEVERITY_CRITICAL , PSTR ( " Rejected go around command. " ) ) ;
2014-10-21 12:26:33 -03:00
}
break ;
2014-02-13 18:49:42 -04:00
case MAV_CMD_DO_FENCE_ENABLE :
result = MAV_RESULT_ACCEPTED ;
2015-05-13 03:09:36 -03:00
if ( ! plane . geofence_present ( ) ) {
2014-02-13 18:49:42 -04:00
result = MAV_RESULT_FAILED ;
2014-03-25 22:42:58 -03:00
} switch ( ( uint16_t ) packet . param1 ) {
case 0 :
2015-05-13 03:09:36 -03:00
if ( ! plane . geofence_set_enabled ( false , GCS_TOGGLED ) ) {
2014-02-13 18:49:42 -04:00
result = MAV_RESULT_FAILED ;
}
2015-05-08 03:27:16 -03:00
break ;
2014-03-25 22:42:58 -03:00
case 1 :
2015-05-13 03:09:36 -03:00
if ( ! plane . geofence_set_enabled ( true , GCS_TOGGLED ) ) {
2014-02-13 18:49:42 -04:00
result = MAV_RESULT_FAILED ;
}
2015-05-08 03:27:16 -03:00
break ;
2015-04-09 13:02:38 -03:00
case 2 : //disable fence floor only
2015-05-13 03:09:36 -03:00
if ( ! plane . geofence_set_floor_enabled ( false ) ) {
2015-04-09 13:02:38 -03:00
result = MAV_RESULT_FAILED ;
} else {
2015-08-25 18:28:50 -03:00
plane . gcs_send_text_P ( MAV_SEVERITY_CRITICAL , PSTR ( " Fence floor disabled. " ) ) ;
2015-04-09 13:02:38 -03:00
}
2015-05-08 03:27:16 -03:00
break ;
2014-03-25 22:42:58 -03:00
default :
result = MAV_RESULT_FAILED ;
2015-05-08 03:27:16 -03:00
break ;
2014-02-13 18:49:42 -04:00
}
break ;
2015-02-11 18:04:25 -04:00
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES : {
2015-05-04 23:34:27 -03:00
if ( is_equal ( packet . param1 , 1.0f ) ) {
2015-08-21 14:37:13 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_autopilot_version ( FIRMWARE_VERSION ) ;
2015-02-11 18:04:25 -04:00
result = MAV_RESULT_ACCEPTED ;
}
break ;
2015-02-20 19:14:18 -04:00
case MAV_CMD_DO_SET_HOME :
// param1 : use current (1=use current location, 0=use specified location)
// param5 : latitude
// param6 : longitude
// param7 : altitude (absolute)
result = MAV_RESULT_FAILED ; // assume failure
2015-05-04 23:34:27 -03:00
if ( is_equal ( packet . param1 , 1.0f ) ) {
2015-05-13 03:09:36 -03:00
plane . init_home ( ) ;
2015-02-20 19:14:18 -04:00
} else {
2015-05-04 23:34:27 -03:00
if ( is_zero ( packet . param5 ) & & is_zero ( packet . param6 ) & & is_zero ( packet . param7 ) ) {
2015-02-20 19:14:18 -04:00
// don't allow the 0,0 position
break ;
}
2015-08-27 02:40:14 -03:00
// sanity check location
if ( fabsf ( packet . param5 ) > 90.0f | | fabsf ( packet . param6 ) > 180.0f ) {
break ;
}
2015-06-04 00:18:04 -03:00
Location new_home_loc { } ;
2015-02-20 19:14:18 -04:00
new_home_loc . lat = ( int32_t ) ( packet . param5 * 1.0e7 f ) ;
new_home_loc . lng = ( int32_t ) ( packet . param6 * 1.0e7 f ) ;
new_home_loc . alt = ( int32_t ) ( packet . param7 * 100.0f ) ;
2015-05-13 03:09:36 -03:00
plane . ahrs . set_home ( new_home_loc ) ;
plane . home_is_set = HOME_SET_NOT_LOCKED ;
2015-07-05 23:01:17 -03:00
plane . Log_Write_Home_And_Origin ( ) ;
2015-02-20 19:14:18 -04:00
result = MAV_RESULT_ACCEPTED ;
2015-06-04 00:18:04 -03:00
plane . gcs_send_text_fmt ( PSTR ( " set home to %.6f %.6f at %um " ) ,
2015-07-05 04:26:30 -03:00
( double ) ( new_home_loc . lat * 1.0e-7 f ) ,
( double ) ( new_home_loc . lng * 1.0e-7 f ) ,
( uint32_t ) ( new_home_loc . alt * 0.01f ) ) ;
2015-02-20 19:14:18 -04:00
}
break ;
2015-02-11 18:04:25 -04:00
}
2015-06-13 06:16:02 -03:00
case MAV_CMD_DO_AUTOTUNE_ENABLE :
// param1 : enable/disable
2015-07-05 04:26:30 -03:00
plane . autotune_enable ( ! is_zero ( packet . param1 ) ) ;
2015-06-13 06:16:02 -03:00
break ;
2015-07-31 00:21:50 -03:00
case MAV_CMD_DO_START_MAG_CAL :
case MAV_CMD_DO_ACCEPT_MAG_CAL :
case MAV_CMD_DO_CANCEL_MAG_CAL :
result = plane . compass . handle_mag_cal_command ( packet ) ;
break ;
2015-06-13 06:16:02 -03:00
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 :
{
2015-05-24 20:24:11 -03:00
handle_set_mode ( msg , FUNCTOR_BIND ( & plane , & Plane : : mavlink_set_mode , bool , uint8_t ) ) ;
2012-08-21 23:19:51 -03:00
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 :
{
2015-05-13 03:09:36 -03:00
handle_mission_request_list ( plane . 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
{
2015-05-13 03:09:36 -03:00
handle_mission_request ( plane . 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
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , 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)
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION ) ) ;
2014-01-14 00:37:03 -04:00
# 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 :
{
2015-05-13 03:09:36 -03:00
handle_mission_clear_all ( plane . 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-08-04 07:39:15 -03:00
// disable cross-track when user asks for WP change, to
// prevent unexpected flight paths
2015-05-13 03:09:36 -03:00
plane . auto_state . next_wp_no_crosstrack = true ;
handle_mission_set_current ( plane . mission , msg ) ;
if ( plane . control_mode = = AUTO & & plane . mission . state ( ) = = AP_Mission : : MISSION_STOPPED ) {
plane . mission . resume ( ) ;
2014-03-20 20:21:37 -03:00
}
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
{
2015-05-13 03:09:36 -03:00
handle_mission_count ( plane . 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
{
2015-05-13 03:09:36 -03:00
handle_mission_write_partial_list ( plane . mission , msg ) ;
2012-08-21 23:19:51 -03:00
break ;
}
2015-06-23 23:13:16 -03:00
// GCS has sent us a mission item, 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
{
2015-05-13 03:09:36 -03:00
if ( handle_mission_item ( msg , plane . mission ) ) {
2015-06-23 23:13:16 -03:00
plane . DataFlash . Log_Write_EntireMission ( plane . mission ) ;
2015-05-05 18:32:06 -03:00
}
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 ) ;
2015-05-13 03:09:36 -03:00
if ( plane . g . fence_action ! = FENCE_ACTION_NONE ) {
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " fencing must be disabled " ) ) ;
2015-05-13 03:09:36 -03:00
} else if ( packet . count ! = plane . g . fence_total ) {
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " bad fence point " ) ) ;
2015-08-27 02:40:14 -03:00
} else if ( fabsf ( packet . lat ) > 90.0f | | fabsf ( packet . lng ) > 180.0f ) {
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " invalid fence point, lat or lng too large " ) ) ;
2011-12-15 03:09:29 -04:00
} else {
2011-12-15 22:48:15 -04:00
Vector2l point ;
2014-07-08 07:26:07 -03:00
point . x = packet . lat * 1.0e7 f ;
point . y = packet . lng * 1.0e7 f ;
2015-05-13 03:09:36 -03:00
plane . set_fence_point_with_index ( point , packet . idx ) ;
2011-12-15 03:09:29 -04:00
}
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 ) ;
2015-05-13 03:09:36 -03:00
if ( packet . idx > = plane . g . fence_total ) {
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " bad fence point " ) ) ;
2011-12-15 03:09:29 -04:00
} else {
2015-05-13 03:09:36 -03:00
Vector2l point = plane . get_fence_point_with_index ( packet . idx ) ;
mavlink_msg_fence_point_send_buf ( msg , chan , msg - > sysid , msg - > compid , packet . idx , plane . g . fence_total ,
2015-05-02 06:32:27 -03:00
point . x * 1.0e-7 f , point . y * 1.0e-7 f ) ;
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 ) ;
2015-05-13 03:09:36 -03:00
if ( packet . idx > = plane . rally . get_rally_total ( ) | |
packet . idx > = plane . rally . get_rally_max ( ) ) {
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " bad rally point message ID " ) ) ;
2013-10-02 23:20:54 -03:00
break ;
}
2015-05-13 03:09:36 -03:00
if ( packet . count ! = plane . rally . get_rally_total ( ) ) {
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " bad rally point message count " ) ) ;
2013-10-02 23:20:54 -03:00
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 ;
2015-05-13 03:09:36 -03:00
plane . 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 ) ;
2015-05-13 03:09:36 -03:00
if ( packet . idx > plane . rally . get_rally_total ( ) ) {
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " bad rally point index " ) ) ;
2013-10-02 23:20:54 -03:00
break ;
}
RallyLocation rally_point ;
2015-05-13 03:09:36 -03:00
if ( ! plane . rally . get_rally_point_with_index ( packet . idx , rally_point ) ) {
2015-08-25 18:28:50 -03:00
send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " failed to set rally point " ) ) ;
2013-10-02 23:20:54 -03:00
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 ,
2015-05-13 03:09:36 -03:00
plane . 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
{
2015-05-13 03:09:36 -03:00
handle_param_set ( msg , & plane . 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
2015-05-25 19:30:30 -03:00
case MAVLINK_MSG_ID_GIMBAL_REPORT :
{
# if MOUNT == ENABLED
handle_gimbal_report ( plane . camera_mount , msg ) ;
# endif
break ;
}
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.
2015-05-13 03:09:36 -03:00
if ( msg - > sysid ! = plane . g . sysid_my_gcs ) break ; // Only accept control from our gcs
2012-08-21 23:19:51 -03:00
mavlink_rc_channels_override_t packet ;
int16_t v [ 8 ] ;
mavlink_msg_rc_channels_override_decode ( msg , & packet ) ;
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 ) ) {
2015-05-13 19:05:32 -03:00
plane . failsafe . last_valid_rc_ms = plane . millis ( ) ;
2014-04-28 18:47:01 -03:00
}
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
2015-05-13 19:05:32 -03:00
plane . failsafe . last_heartbeat_ms = plane . 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
2015-05-13 03:09:36 -03:00
if ( msg - > sysid ! = plane . g . sysid_my_gcs ) break ;
2015-05-13 19:05:32 -03:00
plane . failsafe . last_heartbeat_ms = plane . millis ( ) ;
2012-08-21 23:19:51 -03:00
break ;
}
2011-09-08 22:29:39 -03:00
2012-08-21 23:19:51 -03:00
case MAVLINK_MSG_ID_HIL_STATE :
{
2015-07-13 03:07:40 -03:00
# if HIL_SUPPORT
2015-05-13 03:09:36 -03:00
if ( plane . g . hil_mode ! = 1 ) {
2015-03-13 08:33:48 -03:00
break ;
}
2012-08-21 23:19:51 -03:00
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 ;
2014-08-09 09:47:40 -03:00
memset ( & loc , 0 , sizeof ( loc ) ) ;
2014-03-28 16:52:48 -03:00
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-08-10 05:17:12 -03:00
// setup airspeed pressure based on 3D speed, no wind
2015-05-13 03:09:36 -03:00
plane . airspeed . setHIL ( sq ( vel . length ( ) ) / 2.0f + 2013 ) ;
2014-08-10 05:17:12 -03:00
2015-05-13 03:09:36 -03:00
plane . gps . setHIL ( 0 , AP_GPS : : GPS_OK_FIX_3D ,
packet . time_usec / 1000 ,
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 ;
2015-03-13 08:33:48 -03:00
accels . x = packet . xacc * GRAVITY_MSS * 0.001f ;
accels . y = packet . yacc * GRAVITY_MSS * 0.001f ;
accels . z = packet . zacc * GRAVITY_MSS * 0.001f ;
2012-07-04 21:55:58 -03:00
2015-05-13 03:09:36 -03:00
plane . ins . set_gyro ( 0 , gyros ) ;
plane . ins . set_accel ( 0 , accels ) ;
2012-08-21 23:19:51 -03:00
2015-05-13 03:09:36 -03:00
plane . barometer . setHIL ( packet . alt * 0.001f ) ;
plane . compass . setHIL ( 0 , packet . roll , packet . pitch , packet . yaw ) ;
plane . compass . setHIL ( 1 , packet . roll , packet . pitch , packet . yaw ) ;
2013-11-22 21:37:05 -04:00
// cope with DCM getting badly off due to HIL lag
2015-05-13 03:09:36 -03:00
if ( plane . g . hil_err_limit > 0 & &
( fabsf ( packet . roll - plane . ahrs . roll ) > ToRad ( plane . g . hil_err_limit ) | |
fabsf ( packet . pitch - plane . ahrs . pitch ) > ToRad ( plane . g . hil_err_limit ) | |
wrap_PI ( fabsf ( packet . yaw - plane . ahrs . yaw ) ) > ToRad ( plane . g . hil_err_limit ) ) ) {
plane . ahrs . reset_attitude ( packet . roll , packet . pitch , packet . yaw ) ;
2013-11-22 21:37:05 -04:00
}
2015-07-13 03:07:40 -03:00
# endif
2012-08-21 23:19:51 -03:00
break ;
}
2011-10-31 18:55:58 -03:00
2012-06-13 16:00:20 -03:00
# if CAMERA == ENABLED
2015-09-06 17:44:33 -03:00
//deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
2012-06-13 16:00:20 -03:00
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE :
2012-08-21 23:19:51 -03:00
{
break ;
}
2012-06-13 16:00:20 -03:00
2015-09-06 17:44:33 -03:00
//deprecated. Use MAV_CMD_DO_DIGICAM_CONTROL
2012-06-13 16:00:20 -03:00
case MAVLINK_MSG_ID_DIGICAM_CONTROL :
2012-08-21 23:19:51 -03:00
{
2015-05-13 03:09:36 -03:00
plane . camera . control_msg ( msg ) ;
plane . log_picture ( ) ;
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
2015-09-06 17:44:33 -03:00
//deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
2011-10-31 18:55:58 -03:00
case MAVLINK_MSG_ID_MOUNT_CONFIGURE :
2012-08-21 23:19:51 -03:00
{
2015-05-13 03:09:36 -03:00
plane . camera_mount . configure_msg ( msg ) ;
2012-08-21 23:19:51 -03:00
break ;
}
2011-10-31 18:55:58 -03:00
2015-09-06 17:44:33 -03:00
//deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
2011-10-31 18:55:58 -03:00
case MAVLINK_MSG_ID_MOUNT_CONTROL :
2012-08-21 23:19:51 -03:00
{
2015-05-13 03:09:36 -03:00
plane . camera_mount . control_msg ( msg ) ;
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
{
2015-05-13 03:09:36 -03:00
handle_radio_status ( msg , plane . DataFlash , plane . 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 :
2015-05-13 03:09:36 -03:00
plane . in_log_download = true ;
2014-01-13 22:51:49 -04:00
// fallthru
case MAVLINK_MSG_ID_LOG_REQUEST_LIST :
2015-05-13 03:09:36 -03:00
if ( ! plane . in_mavlink_delay ) {
handle_log_message ( msg , plane . DataFlash ) ;
2014-01-13 22:51:49 -04:00
}
break ;
case MAVLINK_MSG_ID_LOG_REQUEST_END :
2015-05-13 03:09:36 -03:00
plane . in_log_download = false ;
if ( ! plane . in_mavlink_delay ) {
handle_log_message ( msg , plane . DataFlash ) ;
2013-12-15 03:59:23 -04:00
}
break ;
2014-04-04 17:08:05 -03:00
# if HAL_CPU_CLASS > HAL_CPU_CLASS_16
case MAVLINK_MSG_ID_SERIAL_CONTROL :
2015-05-13 03:09:36 -03:00
handle_serial_control ( msg , plane . gps ) ;
2014-04-04 17:08:05 -03:00
break ;
2015-03-25 01:01:36 -03:00
case MAVLINK_MSG_ID_GPS_INJECT_DATA :
2015-05-13 03:09:36 -03:00
handle_gps_inject ( msg , plane . gps ) ;
2015-03-25 01:01:36 -03:00
break ;
2014-04-04 17:08:05 -03:00
# endif
2014-07-21 19:24:00 -03:00
case MAVLINK_MSG_ID_TERRAIN_DATA :
2014-07-22 05:08:03 -03:00
case MAVLINK_MSG_ID_TERRAIN_CHECK :
2014-07-24 18:58:39 -03:00
# if AP_TERRAIN_AVAILABLE
2015-05-13 03:09:36 -03:00
plane . terrain . handle_data ( chan , msg ) ;
2014-07-21 19:24:00 -03:00
# endif
break ;
2015-02-11 04:52:50 -04:00
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST :
2015-08-21 14:37:13 -03:00
plane . gcs [ chan - MAVLINK_COMM_0 ] . send_autopilot_version ( FIRMWARE_VERSION ) ;
2015-02-11 04:52:50 -04:00
break ;
2014-07-21 19:24:00 -03:00
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
*/
2015-05-13 03:09:36 -03:00
void Plane : : 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 ;
2015-05-13 19:05:32 -03:00
uint32_t tnow = millis ( ) ;
2012-12-04 18:22:21 -04:00
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 ;
2015-08-25 18:28:50 -03:00
gcs_send_text_P ( MAV_SEVERITY_WARNING , PSTR ( " Initialising APM... " ) ) ;
2012-12-04 18:22:21 -04:00
}
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
*/
2015-05-13 03:09:36 -03:00
void Plane : : gcs_send_message ( enum ap_message id )
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 ] . send_message ( id ) ;
}
2011-11-20 05:31:45 -04:00
}
2011-09-18 00:46:42 -03:00
}
2015-07-20 03:11:34 -03:00
/*
* send a mission item reached message and load the index before the send attempt in case it may get delayed
*/
void Plane : : gcs_send_mission_item_reached_message ( uint16_t mission_index )
{
for ( uint8_t i = 0 ; i < num_gcs ; i + + ) {
if ( gcs [ i ] . initialised ) {
gcs [ i ] . mission_item_reached_index = mission_index ;
gcs [ i ] . send_message ( MSG_MISSION_ITEM_REACHED ) ;
}
}
}
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
*/
2015-05-13 03:09:36 -03:00
void Plane : : 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
*/
2015-05-13 03:09:36 -03:00
void Plane : : gcs_update ( void )
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 ) {
2014-05-20 23:44:05 -03:00
# if CLI_ENABLED == ENABLED
2015-05-24 20:24:11 -03:00
gcs [ i ] . update ( g . cli_enabled = = 1 ? FUNCTOR_BIND_MEMBER ( & Plane : : run_cli , void , AP_HAL : : UARTDriver * ) : NULL ) ;
2014-05-20 23:44:05 -03:00
# 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
}
2015-08-25 18:28:50 -03:00
void Plane : : gcs_send_text_P ( MAV_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
*/
2015-05-13 03:09:36 -03:00
void Plane : : 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 ;
2015-08-25 18:28:50 -03:00
gcs [ 0 ] . pending_status . severity = ( uint8_t ) MAV_SEVERITY_WARNING ;
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
*/
2015-05-13 03:09:36 -03:00
void Plane : : gcs_send_airspeed_calibration ( const Vector3f & vg )
2013-08-28 09:36:59 -03:00
{
2013-11-22 04:18:19 -04:00
for ( uint8_t i = 0 ; i < num_gcs ; i + + ) {
2014-08-06 10:17:26 -03:00
if ( gcs [ i ] . initialised ) {
if ( comm_get_txspace ( ( mavlink_channel_t ) i ) - MAVLINK_NUM_NON_PAYLOAD_BYTES > =
MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN ) {
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
*/
2015-05-13 03:09:36 -03:00
void Plane : : gcs_retry_deferred ( void )
2013-10-14 19:52:23 -03:00
{
gcs_send_message ( MSG_RETRY_DEFERRED ) ;
}