2015-05-29 23:12:49 -03:00
# include "Copter.h"
2016-05-27 09:59:22 -03:00
# include "GCS_Mavlink.h"
2015-05-29 23:12:49 -03:00
void Copter : : gcs_send_heartbeat ( void )
2013-01-08 01:45:12 -04:00
{
2017-07-07 22:43:24 -03:00
gcs ( ) . send_message ( MSG_HEARTBEAT ) ;
2013-01-08 01:45:12 -04:00
}
2013-01-06 20:04:00 -04:00
2015-05-29 23:12:49 -03:00
void Copter : : gcs_send_deferred ( void )
2013-01-08 01:45:12 -04:00
{
2017-07-18 22:37:32 -03:00
gcs ( ) . retry_deferred ( ) ;
2012-12-13 10:09:26 -04:00
}
2011-10-11 06:12:37 -03:00
/*
2012-08-16 21:50:03 -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-10-11 06:12:37 -03:00
*/
2018-03-22 05:50:24 -03:00
MAV_TYPE GCS_MAVLINK_Copter : : frame_type ( ) const
2011-10-11 06:12:37 -03:00
{
2018-03-22 05:50:24 -03:00
return copter . get_frame_mav_type ( ) ;
}
2014-10-16 06:08:24 -03:00
2018-03-22 05:50:24 -03:00
MAV_MODE GCS_MAVLINK_Copter : : base_mode ( ) const
{
2018-04-03 11:35:32 -03:00
uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED ;
2012-04-24 06:53:24 -03:00
// work out the base_mode. This value is not very useful
// for APM, but we calculate it as best we can so a generic
// MAVLink enabled ground station can work out something about
// what the MAV is up to. The actual bit values are highly
// ambiguous for most of the APM flight modes. In practice, you
// only get useful information from the custom_mode, which maps to
// the APM flight mode and has a well defined meaning in the
// ArduPlane documentation
2018-03-22 05:50:24 -03:00
switch ( copter . control_mode ) {
2012-04-24 06:53:24 -03:00
case AUTO :
case RTL :
case LOITER :
2016-08-12 18:44:55 -03:00
case AVOID_ADSB :
2018-02-05 22:44:05 -04:00
case FOLLOW :
2012-04-24 06:53:24 -03:00
case GUIDED :
case CIRCLE :
2014-07-11 02:08:09 -03:00
case POSHOLD :
2015-05-17 00:22:20 -03:00
case BRAKE :
2017-09-08 23:45:31 -03:00
case SMART_RTL :
2018-04-03 11:35:32 -03:00
_base_mode | = MAV_MODE_FLAG_GUIDED_ENABLED ;
2012-04-24 06:53:24 -03:00
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
// APM does in any mode, as that is defined as "system finds its own goal
// positions", which APM does not currently do
break ;
2016-01-25 17:26:20 -04:00
default :
break ;
2012-04-24 06:53:24 -03:00
}
// all modes except INITIALISING have some form of manual
// override if stick mixing is enabled
2018-04-03 11:35:32 -03:00
_base_mode | = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED ;
2012-04-24 06:53:24 -03:00
# if HIL_MODE != HIL_MODE_DISABLED
2018-04-03 11:35:32 -03:00
_base_mode | = MAV_MODE_FLAG_HIL_ENABLED ;
2012-04-24 06:53:24 -03:00
# endif
// we are armed if we are not initialising
2018-03-22 05:50:24 -03:00
if ( copter . motors ! = nullptr & & copter . motors - > armed ( ) ) {
2018-04-03 11:35:32 -03:00
_base_mode | = MAV_MODE_FLAG_SAFETY_ARMED ;
2012-04-24 06:53:24 -03:00
}
// indicate we have set a custom mode
2018-04-03 11:35:32 -03:00
_base_mode | = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED ;
2012-04-24 06:53:24 -03:00
2018-04-03 11:35:32 -03:00
return ( MAV_MODE ) _base_mode ;
2018-03-22 05:50:24 -03:00
}
uint32_t GCS_MAVLINK_Copter : : custom_mode ( ) const
{
return copter . control_mode ;
}
MAV_STATE GCS_MAVLINK_Copter : : system_status ( ) const
{
// set system as critical if any failsafe have triggered
if ( copter . any_failsafe_triggered ( ) ) {
return MAV_STATE_CRITICAL ;
}
if ( copter . ap . land_complete ) {
return MAV_STATE_STANDBY ;
}
return MAV_STATE_ACTIVE ;
2011-10-11 06:12:37 -03:00
}
2018-03-22 05:50:24 -03:00
2015-05-29 23:12:49 -03:00
NOINLINE void Copter : : send_attitude ( mavlink_channel_t chan )
2011-10-11 06:12:37 -03:00
{
2014-02-03 03:25:53 -04:00
const Vector3f & gyro = ins . get_gyro ( ) ;
2011-10-11 06:12:37 -03:00
mavlink_msg_attitude_send (
chan ,
2012-07-19 22:57:15 -03:00
millis ( ) ,
2012-03-11 05:36:12 -03:00
ahrs . roll ,
ahrs . pitch ,
ahrs . yaw ,
2014-02-03 03:25:53 -04:00
gyro . x ,
gyro . y ,
gyro . z ) ;
2011-10-11 06:12:37 -03:00
}
2013-04-26 06:51:07 -03:00
# if AC_FENCE == ENABLED
2017-01-11 21:50:32 -04:00
NOINLINE void Copter : : send_fence_status ( mavlink_channel_t chan )
2012-07-14 23:26:17 -03:00
{
2013-04-26 06:51:07 -03:00
fence_send_mavlink_status ( chan ) ;
2012-07-14 23:26:17 -03:00
}
# endif
2015-05-29 23:12:49 -03:00
NOINLINE void Copter : : send_extended_status1 ( mavlink_channel_t chan )
2011-10-11 06:12:37 -03:00
{
2013-10-01 10:34:44 -03:00
int16_t battery_current = - 1 ;
int8_t battery_remaining = - 1 ;
2012-06-24 21:01:25 -03:00
2015-03-18 08:09:49 -03:00
if ( battery . has_current ( ) & & battery . healthy ( ) ) {
2013-10-01 10:34:44 -03:00
battery_remaining = battery . capacity_remaining_pct ( ) ;
battery_current = battery . current_amps ( ) * 100 ;
2012-06-24 21:01:25 -03:00
}
2016-10-27 20:05:40 -03:00
update_sensor_status_flags ( ) ;
2012-04-24 06:53:24 -03:00
mavlink_msg_sys_status_send (
chan ,
control_sensors_present ,
control_sensors_enabled ,
control_sensors_health ,
2017-07-30 02:09:34 -03:00
( uint16_t ) ( scheduler . load_average ( ) * 1000 ) ,
2013-10-01 10:34:44 -03:00
battery . voltage ( ) * 1000 , // mV
2012-06-24 21:01:25 -03:00
battery_current , // in 10mA units
2012-04-24 06:53:24 -03:00
battery_remaining , // in %
0 , // comm drops %,
0 , // comm drops in pkts,
0 , 0 , 0 , 0 ) ;
2011-10-11 06:12:37 -03:00
}
2015-05-29 23:12:49 -03:00
void NOINLINE Copter : : send_location ( mavlink_channel_t chan )
2011-10-11 06:12:37 -03:00
{
2018-02-07 19:24:37 -04:00
const uint32_t now = AP_HAL : : millis ( ) ;
Vector3f vel ;
ahrs . get_velocity_NED ( vel ) ;
2011-10-11 06:12:37 -03:00
mavlink_msg_global_position_int_send (
chan ,
2018-02-07 19:24:37 -04:00
now ,
2012-04-24 06:53:24 -03:00
current_loc . lat , // in 1E7 degrees
current_loc . lng , // in 1E7 degrees
2015-01-05 04:50:14 -04:00
( ahrs . get_home ( ) . alt + current_loc . alt ) * 10UL , // millimeters above sea level
2014-06-10 23:03:19 -03:00
current_loc . alt * 10 , // millimeters above ground
2018-02-07 19:24:37 -04: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 Down)
2013-12-03 02:41:23 -04:00
ahrs . yaw_sensor ) ; // compass heading in 1/100 degree
2011-10-11 06:12:37 -03:00
}
2015-05-29 23:12:49 -03:00
void NOINLINE Copter : : send_nav_controller_output ( mavlink_channel_t chan )
2011-10-11 06:12:37 -03:00
{
2017-01-09 03:31:26 -04:00
const Vector3f & targets = attitude_control - > get_att_target_euler_cd ( ) ;
2011-10-11 06:12:37 -03:00
mavlink_msg_nav_controller_output_send (
chan ,
2017-06-19 02:39:56 -03:00
targets . x * 1.0e-2 f ,
targets . y * 1.0e-2 f ,
targets . z * 1.0e-2 f ,
2017-12-05 21:28:32 -04:00
flightmode - > wp_bearing ( ) * 1.0e-2 f ,
MIN ( flightmode - > wp_distance ( ) * 1.0e-2 f , UINT16_MAX ) ,
2017-06-19 02:39:56 -03:00
pos_control - > get_alt_error ( ) * 1.0e-2 f ,
2011-12-31 03:37:24 -04:00
0 ,
2013-03-17 04:46:31 -03:00
0 ) ;
2011-10-11 06:12:37 -03:00
}
2012-03-01 08:36:35 -04:00
// report simulator state
2015-05-29 23:12:49 -03:00
void NOINLINE Copter : : send_simstate ( mavlink_channel_t chan )
2012-03-01 08:36:35 -04:00
{
2015-05-04 03:18:46 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2012-06-29 02:10:35 -03:00
sitl . simstate_send ( chan ) ;
2012-03-01 08:36:35 -04:00
# endif
2013-04-05 10:25:58 -03:00
}
2012-03-01 08:36:35 -04:00
2015-05-29 23:12:49 -03:00
void NOINLINE Copter : : send_vfr_hud ( mavlink_channel_t chan )
2011-10-11 06:12:37 -03:00
{
mavlink_msg_vfr_hud_send (
chan ,
2014-03-31 04:07:46 -03:00
gps . ground_speed ( ) ,
2016-10-26 11:02:55 -03:00
ahrs . groundspeed ( ) ,
2012-03-11 05:36:12 -03:00
( ahrs . yaw_sensor / 100 ) % 360 ,
2017-01-09 03:31:26 -04:00
( int16_t ) ( motors - > get_throttle ( ) * 100 ) ,
2013-01-10 14:42:24 -04:00
current_loc . alt / 100.0f ,
climb_rate / 100.0f ) ;
2011-10-11 06:12:37 -03:00
}
2015-08-07 02:34:56 -03:00
/*
send RPM packet
*/
void NOINLINE Copter : : send_rpm ( mavlink_channel_t chan )
{
2018-03-29 10:49:27 -03:00
# if RPM_ENABLED == ENABLED
2015-11-19 22:06:14 -04:00
if ( rpm_sensor . enabled ( 0 ) | | rpm_sensor . enabled ( 1 ) ) {
2015-08-07 02:34:56 -03:00
mavlink_msg_rpm_send (
chan ,
rpm_sensor . get_rpm ( 0 ) ,
rpm_sensor . get_rpm ( 1 ) ) ;
}
2018-03-29 10:49:27 -03:00
# endif
2015-08-07 02:34:56 -03:00
}
2015-05-22 21:04:54 -03:00
/*
send PID tuning message
*/
2015-05-29 23:12:49 -03:00
void Copter : : send_pid_tuning ( mavlink_channel_t chan )
2015-05-22 21:04:54 -03:00
{
const Vector3f & gyro = ahrs . get_gyro ( ) ;
if ( g . gcs_pid_mask & 1 ) {
2017-01-09 03:31:26 -04:00
const DataFlash_Class : : PID_Info & pid_info = attitude_control - > get_rate_roll_pid ( ) . get_pid_info ( ) ;
2018-02-11 20:39:54 -04:00
mavlink_msg_pid_tuning_send ( chan , PID_TUNING_ROLL ,
2015-05-22 21:04:54 -03:00
pid_info . desired * 0.01f ,
degrees ( gyro . x ) ,
2015-07-02 02:22:53 -03:00
pid_info . FF * 0.01f ,
pid_info . P * 0.01f ,
pid_info . I * 0.01f ,
pid_info . D * 0.01f ) ;
2015-05-22 21:04:54 -03:00
if ( ! HAVE_PAYLOAD_SPACE ( chan , PID_TUNING ) ) {
return ;
}
}
if ( g . gcs_pid_mask & 2 ) {
2017-01-09 03:31:26 -04:00
const DataFlash_Class : : PID_Info & pid_info = attitude_control - > get_rate_pitch_pid ( ) . get_pid_info ( ) ;
2018-02-11 20:39:54 -04:00
mavlink_msg_pid_tuning_send ( chan , PID_TUNING_PITCH ,
2015-05-22 21:04:54 -03:00
pid_info . desired * 0.01f ,
degrees ( gyro . y ) ,
pid_info . FF * 0.01f ,
pid_info . P * 0.01f ,
pid_info . I * 0.01f ,
pid_info . D * 0.01f ) ;
if ( ! HAVE_PAYLOAD_SPACE ( chan , PID_TUNING ) ) {
return ;
}
}
if ( g . gcs_pid_mask & 4 ) {
2017-01-09 03:31:26 -04:00
const DataFlash_Class : : PID_Info & pid_info = attitude_control - > get_rate_yaw_pid ( ) . get_pid_info ( ) ;
2018-02-11 20:39:54 -04:00
mavlink_msg_pid_tuning_send ( chan , PID_TUNING_YAW ,
2015-05-22 21:04:54 -03:00
pid_info . desired * 0.01f ,
degrees ( gyro . z ) ,
pid_info . FF * 0.01f ,
pid_info . P * 0.01f ,
pid_info . I * 0.01f ,
2015-05-24 03:00:25 -03:00
pid_info . D * 0.01f ) ;
if ( ! HAVE_PAYLOAD_SPACE ( chan , PID_TUNING ) ) {
return ;
}
}
if ( g . gcs_pid_mask & 8 ) {
2017-11-20 21:49:11 -04:00
const DataFlash_Class : : PID_Info & pid_info = copter . pos_control - > get_accel_z_pid ( ) . get_pid_info ( ) ;
2018-02-11 20:39:54 -04:00
mavlink_msg_pid_tuning_send ( chan , PID_TUNING_ACCZ ,
2015-05-24 03:00:25 -03:00
pid_info . desired * 0.01f ,
- ( ahrs . get_accel_ef_blended ( ) . z + GRAVITY_MSS ) ,
pid_info . FF * 0.01f ,
pid_info . P * 0.01f ,
pid_info . I * 0.01f ,
2015-05-22 21:04:54 -03:00
pid_info . D * 0.01f ) ;
if ( ! HAVE_PAYLOAD_SPACE ( chan , PID_TUNING ) ) {
return ;
}
}
}
2017-07-12 04:21:28 -03:00
uint8_t GCS_MAVLINK_Copter : : sysid_my_gcs ( ) const
{
return copter . g . sysid_my_gcs ;
}
2016-05-29 20:54:36 -03:00
uint32_t GCS_MAVLINK_Copter : : telem_delay ( ) const
2012-08-29 20:03:01 -03:00
{
2016-05-29 20:54:36 -03:00
return ( uint32_t ) ( copter . g . telem_delay ) ;
2012-08-29 20:03:01 -03:00
}
2017-07-17 19:51:21 -03:00
// try to send a message, return false if it wasn't sent
2016-05-27 09:59:22 -03:00
bool GCS_MAVLINK_Copter : : try_send_message ( enum ap_message id )
2011-10-11 06:12:37 -03:00
{
2017-07-12 05:10:47 -03:00
if ( telemetry_delayed ( ) ) {
2011-10-11 06:12:37 -03:00
return false ;
}
2013-10-18 20:15:01 -03:00
# if HIL_MODE != HIL_MODE_SENSORS
2013-10-23 02:11:28 -03:00
// if we don't have at least 250 micros remaining before the main loop
2013-01-08 01:45:12 -04:00
// wants to fire then don't send a mavlink message. We want to
// prioritise the main flight control loop over communications
2017-01-26 08:07:16 -04:00
// the check for nullptr here doesn't just save a nullptr
// dereference; it means that we send messages out even if we're
// failing to detect a PX4 board type (see delay(3000) in px_drivers).
if ( copter . motors ! = nullptr & & copter . scheduler . time_available_usec ( ) < 250 & & copter . motors - > armed ( ) ) {
2017-08-20 23:32:58 -03:00
gcs ( ) . set_out_of_time ( true ) ;
2013-01-06 20:02:50 -04:00
return false ;
}
2013-10-18 20:15:01 -03:00
# endif
2013-01-06 20:02:50 -04:00
2012-08-16 21:50:03 -03:00
switch ( id ) {
2011-10-11 06:12:37 -03:00
case MSG_HEARTBEAT :
CHECK_PAYLOAD_SIZE ( HEARTBEAT ) ;
2016-05-16 19:27:01 -03:00
last_heartbeat_time = AP_HAL : : millis ( ) ;
2018-03-22 05:50:24 -03:00
send_heartbeat ( ) ;
2013-01-08 01:45:12 -04:00
break ;
2011-10-11 06:12:37 -03:00
case MSG_EXTENDED_STATUS1 :
2014-09-09 10:17:46 -03:00
// send extended status only once vehicle has been initialised
// to avoid unnecessary errors being reported to user
2015-05-29 23:12:49 -03:00
if ( copter . ap . initialised ) {
2014-09-09 10:17:46 -03:00
CHECK_PAYLOAD_SIZE ( SYS_STATUS ) ;
2015-05-29 23:12:49 -03:00
copter . send_extended_status1 ( chan ) ;
2014-09-09 10:17:46 -03:00
CHECK_PAYLOAD_SIZE ( POWER_STATUS ) ;
2016-05-16 19:27:01 -03:00
send_power_status ( ) ;
2014-09-09 10:17:46 -03:00
}
2011-10-11 06:12:37 -03:00
break ;
case MSG_ATTITUDE :
CHECK_PAYLOAD_SIZE ( ATTITUDE ) ;
2015-05-29 23:12:49 -03:00
copter . send_attitude ( chan ) ;
2011-10-11 06:12:37 -03:00
break ;
case MSG_LOCATION :
CHECK_PAYLOAD_SIZE ( GLOBAL_POSITION_INT ) ;
2015-05-29 23:12:49 -03:00
copter . send_location ( chan ) ;
2011-10-11 06:12:37 -03:00
break ;
case MSG_NAV_CONTROLLER_OUTPUT :
CHECK_PAYLOAD_SIZE ( NAV_CONTROLLER_OUTPUT ) ;
2015-05-29 23:12:49 -03:00
copter . send_nav_controller_output ( chan ) ;
2011-10-11 06:12:37 -03:00
break ;
case MSG_RADIO_IN :
2016-10-13 07:24:02 -03:00
CHECK_PAYLOAD_SIZE ( RC_CHANNELS ) ;
2016-05-16 19:27:01 -03:00
send_radio_in ( copter . receiver_rssi ) ;
2011-10-11 06:12:37 -03:00
break ;
2017-01-10 11:19:55 -04:00
case MSG_SERVO_OUTPUT_RAW :
2011-10-11 06:12:37 -03:00
CHECK_PAYLOAD_SIZE ( SERVO_OUTPUT_RAW ) ;
2016-07-15 07:04:19 -03:00
send_servo_output_raw ( false ) ;
2011-10-11 06:12:37 -03:00
break ;
case MSG_VFR_HUD :
CHECK_PAYLOAD_SIZE ( VFR_HUD ) ;
2015-05-29 23:12:49 -03:00
copter . send_vfr_hud ( chan ) ;
2011-10-11 06:12:37 -03:00
break ;
case MSG_RAW_IMU1 :
CHECK_PAYLOAD_SIZE ( RAW_IMU ) ;
2016-05-16 19:27:01 -03:00
send_raw_imu ( copter . ins , copter . compass ) ;
2011-10-11 06:12:37 -03:00
break ;
case MSG_RAW_IMU2 :
CHECK_PAYLOAD_SIZE ( SCALED_PRESSURE ) ;
2018-03-05 16:37:25 -04:00
send_scaled_pressure ( ) ;
2011-10-11 06:12:37 -03:00
break ;
case MSG_RAW_IMU3 :
CHECK_PAYLOAD_SIZE ( SENSOR_OFFSETS ) ;
2018-03-05 16:37:25 -04:00
send_sensor_offsets ( copter . ins , copter . compass ) ;
2011-10-11 06:12:37 -03:00
break ;
2014-05-16 01:54:24 -03:00
case MSG_RANGEFINDER :
2016-04-27 07:55:35 -03:00
# if RANGEFINDER_ENABLED == ENABLED
2014-05-16 01:54:24 -03:00
CHECK_PAYLOAD_SIZE ( RANGEFINDER ) ;
2017-06-05 15:49:34 -03:00
send_rangefinder_downward ( copter . rangefinder ) ;
2017-05-30 11:15:11 -03:00
CHECK_PAYLOAD_SIZE ( DISTANCE_SENSOR ) ;
send_distance_sensor_downward ( copter . rangefinder ) ;
2014-05-16 01:54:24 -03:00
# endif
2017-07-14 14:00:01 -03:00
# if PROXIMITY_ENABLED == ENABLED
2017-07-14 14:00:18 -03:00
send_proximity ( copter . g2 . proximity ) ;
2017-07-14 14:00:01 -03:00
# endif
2014-10-20 23:59:18 -03:00
break ;
2014-05-16 01:54:24 -03:00
2015-08-07 02:34:56 -03:00
case MSG_RPM :
2018-03-29 10:49:27 -03:00
# if RPM_ENABLED == ENABLED
2015-08-07 02:34:56 -03:00
CHECK_PAYLOAD_SIZE ( RPM ) ;
copter . send_rpm ( chan ) ;
2018-03-29 10:49:27 -03:00
# endif
2015-08-07 02:34:56 -03:00
break ;
2014-07-22 05:22:36 -03:00
case MSG_TERRAIN :
2015-11-13 23:38:47 -04:00
# if AP_TERRAIN_AVAILABLE && AC_TERRAIN
2014-07-22 05:22:36 -03:00
CHECK_PAYLOAD_SIZE ( TERRAIN_REQUEST ) ;
2015-05-29 23:12:49 -03:00
copter . terrain . send_request ( chan ) ;
2014-07-22 05:22:36 -03:00
# endif
break ;
2017-01-11 21:50:32 -04:00
case MSG_FENCE_STATUS :
2014-10-20 23:59:18 -03:00
# if AC_FENCE == ENABLED
2017-01-11 21:50:32 -04:00
CHECK_PAYLOAD_SIZE ( FENCE_STATUS ) ;
copter . send_fence_status ( chan ) ;
2012-07-14 23:26:17 -03:00
# endif
2014-10-20 23:59:18 -03:00
break ;
2012-07-14 23:26:17 -03:00
2012-03-01 08:36:35 -04:00
case MSG_SIMSTATE :
2015-05-04 03:18:46 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2012-03-11 05:36:12 -03:00
CHECK_PAYLOAD_SIZE ( SIMSTATE ) ;
2015-05-29 23:12:49 -03:00
copter . send_simstate ( chan ) ;
2014-01-03 20:30:55 -04:00
# endif
CHECK_PAYLOAD_SIZE ( AHRS2 ) ;
2018-01-05 21:28:00 -04:00
send_ahrs2 ( ) ;
2012-03-01 08:36:35 -04:00
break ;
2014-11-17 19:00:19 -04:00
case MSG_MOUNT_STATUS :
# if MOUNT == ENABLED
2018-02-11 20:39:54 -04:00
CHECK_PAYLOAD_SIZE ( MOUNT_STATUS ) ;
2015-05-29 23:12:49 -03:00
copter . camera_mount . status_msg ( chan ) ;
2014-11-17 19:00:19 -04:00
# endif // MOUNT == ENABLED
break ;
2015-04-15 08:46:43 -03:00
case MSG_BATTERY2 :
CHECK_PAYLOAD_SIZE ( BATTERY2 ) ;
2016-05-16 19:27:01 -03:00
send_battery2 ( copter . battery ) ;
2015-04-15 08:46:43 -03:00
break ;
2014-12-08 01:07:31 -04:00
case MSG_OPTICAL_FLOW :
# if OPTFLOW == ENABLED
CHECK_PAYLOAD_SIZE ( OPTICAL_FLOW ) ;
2018-01-05 21:28:00 -04:00
send_opticalflow ( copter . optflow ) ;
2014-12-08 01:07:31 -04:00
# endif
break ;
2015-01-29 05:02:37 -04:00
case MSG_GIMBAL_REPORT :
# if MOUNT == ENABLED
CHECK_PAYLOAD_SIZE ( GIMBAL_REPORT ) ;
2015-05-29 23:12:49 -03:00
copter . camera_mount . send_gimbal_report ( chan ) ;
2015-01-29 05:02:37 -04:00
# endif
break ;
2015-03-10 04:01:09 -03:00
case MSG_EKF_STATUS_REPORT :
CHECK_PAYLOAD_SIZE ( EKF_STATUS_REPORT ) ;
2015-09-28 21:59:24 -03:00
copter . ahrs . send_ekf_status_report ( chan ) ;
2015-03-10 04:01:09 -03:00
break ;
2015-01-29 05:02:37 -04:00
2017-01-11 21:50:32 -04:00
case MSG_LIMITS_STATUS :
2013-12-15 20:24:27 -04:00
case MSG_WIND :
2016-04-19 20:57:34 -03:00
case MSG_POSITION_TARGET_GLOBAL_INT :
2017-01-06 21:06:40 -04:00
case MSG_SERVO_OUT :
2017-04-19 07:05:53 -03:00
case MSG_AOA_SSA :
2017-05-18 15:31:17 -03:00
case MSG_LANDING :
2013-12-15 20:24:27 -04:00
// unused
break ;
2015-05-22 21:04:54 -03:00
case MSG_PID_TUNING :
CHECK_PAYLOAD_SIZE ( PID_TUNING ) ;
2015-05-29 23:12:49 -03:00
copter . send_pid_tuning ( chan ) ;
2015-05-22 21:04:54 -03:00
break ;
2015-06-12 03:35:58 -03:00
case MSG_VIBRATION :
CHECK_PAYLOAD_SIZE ( VIBRATION ) ;
send_vibration ( copter . ins ) ;
break ;
2016-06-15 21:17:57 -03:00
case MSG_ADSB_VEHICLE :
2018-02-16 10:21:55 -04:00
# if ADSB_ENABLED == ENABLED
2016-06-15 21:17:57 -03:00
CHECK_PAYLOAD_SIZE ( ADSB_VEHICLE ) ;
copter . adsb . send_adsb_vehicle ( chan ) ;
2018-02-16 10:21:55 -04:00
# endif
2016-06-15 21:17:57 -03:00
break ;
2017-04-07 17:14:11 -03:00
case MSG_BATTERY_STATUS :
send_battery_status ( copter . battery ) ;
break ;
2017-07-17 20:54:02 -03:00
default :
return GCS_MAVLINK : : try_send_message ( id ) ;
2012-08-16 21:50:03 -03:00
}
2011-10-11 06:12:37 -03:00
return true ;
}
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo GCS_MAVLINK : : var_info [ ] = {
2013-01-02 10:36:48 -04:00
// @Param: RAW_SENS
// @DisplayName: Raw sensor stream rate
2017-01-05 13:40:02 -04:00
// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " RAW_SENS " , 0 , GCS_MAVLINK , streamRates [ 0 ] , 0 ) ,
2013-01-02 10:36:48 -04:00
// @Param: EXT_STAT
// @DisplayName: Extended status stream rate to ground station
2017-07-03 16:42:04 -03:00
// @Description: Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " EXT_STAT " , 1 , GCS_MAVLINK , streamRates [ 1 ] , 0 ) ,
2013-01-02 10:36:48 -04:00
// @Param: RC_CHAN
// @DisplayName: RC Channel stream rate to ground station
2016-10-13 21:40:09 -03:00
// @Description: Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " RC_CHAN " , 2 , GCS_MAVLINK , streamRates [ 2 ] , 0 ) ,
2013-01-02 10:36:48 -04:00
// @Param: RAW_CTRL
// @DisplayName: Raw Control stream rate to ground station
2014-04-06 06:00:32 -03:00
// @Description: Stream rate of RC_CHANNELS_SCALED (HIL only) to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " RAW_CTRL " , 3 , GCS_MAVLINK , streamRates [ 3 ] , 0 ) ,
2013-01-02 10:36:48 -04:00
// @Param: POSITION
// @DisplayName: Position stream rate to ground station
2017-01-05 13:40:02 -04:00
// @Description: Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " POSITION " , 4 , GCS_MAVLINK , streamRates [ 4 ] , 0 ) ,
2013-01-02 10:36:48 -04:00
// @Param: EXTRA1
// @DisplayName: Extra data type 1 stream rate to ground station
2017-01-05 13:40:02 -04:00
// @Description: Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " EXTRA1 " , 5 , GCS_MAVLINK , streamRates [ 5 ] , 0 ) ,
2013-01-02 10:36:48 -04:00
// @Param: EXTRA2
// @DisplayName: Extra data type 2 stream rate to ground station
2014-04-06 06:00:32 -03:00
// @Description: Stream rate of VFR_HUD to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " EXTRA2 " , 6 , GCS_MAVLINK , streamRates [ 6 ] , 0 ) ,
2013-01-02 10:36:48 -04:00
// @Param: EXTRA3
// @DisplayName: Extra data type 3 stream rate to ground station
2017-01-05 13:40:02 -04:00
// @Description: Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " EXTRA3 " , 7 , GCS_MAVLINK , streamRates [ 7 ] , 0 ) ,
2013-01-02 10:36:48 -04:00
// @Param: PARAMS
// @DisplayName: Parameter stream rate to ground station
2014-04-06 06:00:32 -03:00
// @Description: Stream rate of PARAM_VALUE to ground station
2013-01-02 10:36:48 -04:00
// @Units: Hz
// @Range: 0 10
// @Increment: 1
// @User: Advanced
2013-11-23 06:45:42 -04:00
AP_GROUPINFO ( " PARAMS " , 8 , GCS_MAVLINK , streamRates [ 8 ] , 0 ) ,
2016-06-15 21:17:57 -03:00
// @Param: ADSB
// @DisplayName: ADSB stream rate to ground station
// @Description: ADSB stream rate to ground station
// @Units: Hz
// @Range: 0 50
// @Increment: 1
// @User: Advanced
AP_GROUPINFO ( " ADSB " , 9 , GCS_MAVLINK , streamRates [ 9 ] , 5 ) ,
AP_GROUPEND
2012-02-12 07:27:03 -04:00
} ;
2011-05-11 03:10:06 -03:00
2011-02-21 02:36:05 -04:00
void
2016-05-27 09:59:22 -03:00
GCS_MAVLINK_Copter : : data_stream_send ( void )
2011-02-21 02:36:05 -04:00
{
2013-12-14 22:03:57 -04:00
if ( waypoint_receiving ) {
2012-04-01 22:18:42 -03:00
// don't interfere with mission transfer
return ;
}
2011-05-29 16:32:55 -03:00
2017-08-20 23:32:58 -03:00
gcs ( ) . set_out_of_time ( false ) ;
2013-01-08 01:45:12 -04:00
2017-04-29 01:36:42 -03:00
send_queued_parameters ( ) ;
2012-04-01 22:18:42 -03:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2013-01-08 01:45:12 -04:00
2015-05-29 23:12:49 -03:00
if ( copter . in_mavlink_delay ) {
2012-05-22 03:08:46 -03:00
// don't send any other stream types while in the delay callback
return ;
}
2012-04-01 22:18:42 -03:00
if ( stream_trigger ( STREAM_RAW_SENSORS ) ) {
2017-01-05 13:40:02 -04:00
send_message ( MSG_RAW_IMU1 ) ; // RAW_IMU, SCALED_IMU2, SCALED_IMU3
send_message ( MSG_RAW_IMU2 ) ; // SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3
send_message ( MSG_RAW_IMU3 ) ; // SENSOR_OFFSETS
2012-08-16 21:50:03 -03:00
}
2011-05-29 16:32:55 -03:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2013-01-08 01:45:12 -04:00
2012-04-01 22:18:42 -03:00
if ( stream_trigger ( STREAM_EXTENDED_STATUS ) ) {
2017-01-05 13:40:02 -04:00
send_message ( MSG_EXTENDED_STATUS1 ) ; // SYS_STATUS, POWER_STATUS
send_message ( MSG_EXTENDED_STATUS2 ) ; // MEMINFO
2012-08-16 21:50:03 -03:00
send_message ( MSG_CURRENT_WAYPOINT ) ;
2017-08-08 07:01:48 -03:00
send_message ( MSG_GPS_RAW ) ;
send_message ( MSG_GPS_RTK ) ;
send_message ( MSG_GPS2_RAW ) ;
send_message ( MSG_GPS2_RTK ) ;
2012-08-16 21:50:03 -03:00
send_message ( MSG_NAV_CONTROLLER_OUTPUT ) ;
2017-01-11 21:50:32 -04:00
send_message ( MSG_FENCE_STATUS ) ;
2012-08-16 21:50:03 -03:00
}
2011-02-21 02:36:05 -04:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2013-01-08 01:45:12 -04:00
2012-04-01 22:18:42 -03:00
if ( stream_trigger ( STREAM_POSITION ) ) {
2012-11-27 20:26:19 -04:00
send_message ( MSG_LOCATION ) ;
2015-04-05 12:24:35 -03:00
send_message ( MSG_LOCAL_POSITION ) ;
2012-08-16 21:50:03 -03:00
}
2011-02-21 02:36:05 -04:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2013-01-08 01:45:12 -04:00
2012-04-01 22:18:42 -03:00
if ( stream_trigger ( STREAM_RAW_CONTROLLER ) ) {
2012-08-16 21:50:03 -03:00
}
2011-02-21 02:36:05 -04:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2013-01-08 01:45:12 -04:00
2012-04-01 22:18:42 -03:00
if ( stream_trigger ( STREAM_RC_CHANNELS ) ) {
2017-01-10 11:19:55 -04:00
send_message ( MSG_SERVO_OUTPUT_RAW ) ;
2012-08-16 21:50:03 -03:00
send_message ( MSG_RADIO_IN ) ;
}
2011-02-21 02:36:05 -04:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2013-01-08 01:45:12 -04:00
2012-04-01 22:18:42 -03:00
if ( stream_trigger ( STREAM_EXTRA1 ) ) {
2012-08-16 21:50:03 -03:00
send_message ( MSG_ATTITUDE ) ;
2017-01-05 13:40:02 -04:00
send_message ( MSG_SIMSTATE ) ; // SIMSTATE, AHRS2
2015-05-22 21:04:54 -03:00
send_message ( MSG_PID_TUNING ) ;
2012-08-16 21:50:03 -03:00
}
2011-02-21 02:36:05 -04:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2013-01-08 01:45:12 -04:00
2012-04-01 22:18:42 -03:00
if ( stream_trigger ( STREAM_EXTRA2 ) ) {
2012-08-16 21:50:03 -03:00
send_message ( MSG_VFR_HUD ) ;
}
2011-02-21 02:36:05 -04:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2013-01-08 01:45:12 -04:00
2012-04-01 22:18:42 -03:00
if ( stream_trigger ( STREAM_EXTRA3 ) ) {
2012-08-16 21:50:03 -03:00
send_message ( MSG_AHRS ) ;
send_message ( MSG_HWSTATUS ) ;
2013-10-23 08:15:21 -03:00
send_message ( MSG_SYSTEM_TIME ) ;
2014-05-16 01:54:24 -03:00
send_message ( MSG_RANGEFINDER ) ;
2015-11-13 23:38:47 -04:00
# if AP_TERRAIN_AVAILABLE && AC_TERRAIN
2014-07-22 05:22:36 -03:00
send_message ( MSG_TERRAIN ) ;
# endif
2015-04-15 07:29:52 -03:00
send_message ( MSG_BATTERY2 ) ;
2017-04-07 17:14:11 -03:00
send_message ( MSG_BATTERY_STATUS ) ;
2014-11-17 19:44:02 -04:00
send_message ( MSG_MOUNT_STATUS ) ;
2014-12-08 01:07:31 -04:00
send_message ( MSG_OPTICAL_FLOW ) ;
2015-01-29 05:02:37 -04:00
send_message ( MSG_GIMBAL_REPORT ) ;
2015-03-07 11:51:53 -04:00
send_message ( MSG_MAG_CAL_REPORT ) ;
send_message ( MSG_MAG_CAL_PROGRESS ) ;
2015-03-10 04:01:09 -03:00
send_message ( MSG_EKF_STATUS_REPORT ) ;
2015-06-12 03:35:58 -03:00
send_message ( MSG_VIBRATION ) ;
2015-08-07 02:34:56 -03:00
send_message ( MSG_RPM ) ;
2012-08-16 21:50:03 -03:00
}
2016-06-15 21:17:57 -03:00
2017-08-20 23:32:58 -03:00
if ( gcs ( ) . out_of_time ( ) ) return ;
2016-06-15 21:17:57 -03:00
if ( stream_trigger ( STREAM_ADSB ) ) {
send_message ( MSG_ADSB_VEHICLE ) ;
}
2012-08-16 21:50:03 -03:00
}
2012-04-01 22:18:42 -03:00
2016-05-27 09:59:22 -03:00
bool GCS_MAVLINK_Copter : : handle_guided_request ( AP_Mission : : Mission_Command & cmd )
2014-03-18 20:06:48 -03:00
{
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2017-12-10 22:50:49 -04:00
return copter . mode_auto . do_guided ( cmd ) ;
2018-02-21 22:06:07 -04:00
# else
return false ;
# endif
2014-03-18 20:06:48 -03:00
}
2016-05-27 09:59:22 -03:00
void GCS_MAVLINK_Copter : : handle_change_alt_request ( AP_Mission : : Mission_Command & cmd )
2014-03-18 20:06:48 -03:00
{
// add home alt if needed
2014-06-11 02:41:43 -03:00
if ( cmd . content . location . flags . relative_alt ) {
2015-05-29 23:12:49 -03:00
cmd . content . location . alt + = copter . ahrs . get_home ( ) . alt ;
2014-03-18 20:06:48 -03:00
}
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
}
2016-07-21 09:45:00 -03:00
void GCS_MAVLINK_Copter : : packetReceived ( const mavlink_status_t & status ,
mavlink_message_t & msg )
{
2018-02-16 10:21:55 -04:00
# if ADSB_ENABLED == ENABLED
2016-09-12 03:23:53 -03:00
if ( copter . g2 . dev_options . get ( ) & DevOptionADSBMAVLink ) {
// optional handling of GLOBAL_POSITION_INT as a MAVLink based avoidance source
copter . avoidance_adsb . handle_msg ( msg ) ;
}
2018-02-16 10:21:55 -04:00
# endif
2018-02-06 02:16:09 -04:00
# if MODE_FOLLOW_ENABLED == ENABLED
2018-01-25 08:36:03 -04:00
// pass message to follow library
copter . g2 . follow . handle_msg ( msg ) ;
2018-02-06 02:16:09 -04:00
# endif
2016-07-21 09:45:00 -03:00
GCS_MAVLINK : : packetReceived ( status , msg ) ;
}
2017-08-19 08:23:28 -03:00
bool GCS_MAVLINK_Copter : : params_ready ( ) const
{
if ( AP_BoardConfig : : in_sensor_config_error ( ) ) {
// we may never have parameters "initialised" in this case
return true ;
}
// if we have not yet initialised (including allocating the motors
// object) we drop this request. That prevents the GCS from getting
// a confusing parameter count during bootup
return copter . ap . initialised_params ;
}
void GCS_MAVLINK_Copter : : send_banner ( )
{
GCS_MAVLINK : : send_banner ( ) ;
send_text ( MAV_SEVERITY_INFO , " Frame: %s " , copter . get_frame_string ( ) ) ;
}
2018-03-20 21:19:42 -03:00
void GCS_MAVLINK_Copter : : handle_command_ack ( const mavlink_message_t * msg )
{
copter . command_ack_counter + + ;
GCS_MAVLINK : : handle_command_ack ( msg ) ;
}
2018-03-17 06:12:57 -03:00
MAV_RESULT GCS_MAVLINK_Copter : : _handle_command_preflight_calibration ( const mavlink_command_long_t & packet )
{
if ( is_equal ( packet . param6 , 1.0f ) ) {
// compassmot calibration
return copter . mavlink_compassmot ( chan ) ;
}
return GCS_MAVLINK : : _handle_command_preflight_calibration ( packet ) ;
}
2016-05-27 09:59:22 -03:00
void GCS_MAVLINK_Copter : : handleMessage ( mavlink_message_t * msg )
2011-02-21 02:36:05 -04:00
{
2017-11-27 02:16:41 -04:00
MAV_RESULT result = MAV_RESULT_FAILED ; // assume failure. Each messages id is responsible for return ACK or NAK if required
2013-11-23 06:45:42 -04:00
2012-08-16 21:50:03 -03:00
switch ( msg - > msgid ) {
2011-02-21 02:36:05 -04:00
2014-02-27 21:24:47 -04:00
case MAVLINK_MSG_ID_HEARTBEAT : // MAV ID: 0
2012-08-16 21:50:03 -03:00
{
2014-02-27 21:24:47 -04:00
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
2015-05-29 23:12:49 -03:00
if ( msg - > sysid ! = copter . g . sysid_my_gcs ) break ;
2015-11-19 23:04:45 -04:00
copter . failsafe . last_heartbeat_ms = AP_HAL : : millis ( ) ;
2014-02-27 21:24:47 -04:00
break ;
}
2012-04-24 06:53:24 -03:00
2016-01-05 01:20:48 -04:00
case MAVLINK_MSG_ID_PARAM_VALUE :
{
2016-01-13 23:16:42 -04:00
# if MOUNT == ENABLED
2016-01-05 01:20:48 -04:00
copter . camera_mount . handle_param_value ( msg ) ;
2016-01-13 23:16:42 -04:00
# endif
2016-01-05 01:20:48 -04:00
break ;
}
2014-02-27 21:24:47 -04:00
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM : // MAV ID: 66
{
2014-03-18 18:54:05 -03:00
handle_request_data_stream ( msg , false ) ;
2014-02-27 21:24:47 -04:00
break ;
}
2015-01-29 05:02:37 -04:00
case MAVLINK_MSG_ID_GIMBAL_REPORT :
{
2015-03-21 09:02:06 -03:00
# if MOUNT == ENABLED
2015-05-29 23:12:49 -03:00
handle_gimbal_report ( copter . camera_mount , msg ) ;
2015-03-21 09:02:06 -03:00
# endif
2015-01-29 05:02:37 -04:00
break ;
}
2014-02-27 21:24:47 -04:00
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : // MAV ID: 70
{
// allow override of RC channel values for HIL
// or for complete GCS control of switch position
2012-08-16 21:50:03 -03:00
// and RC PWM values.
2015-05-29 23:12:49 -03:00
if ( msg - > sysid ! = copter . g . sysid_my_gcs ) break ; // Only accept control from our gcs
2018-01-23 08:54:27 -04:00
if ( ! copter . ap . rc_override_enable ) {
if ( copter . failsafe . rc_override_active ) { // if overrides were active previously, disable them
copter . failsafe . rc_override_active = false ;
2018-04-03 23:17:43 -03:00
RC_Channels : : clear_overrides ( ) ;
2018-01-23 08:54:27 -04:00
}
break ;
}
2012-08-16 21:50:03 -03:00
mavlink_rc_channels_override_t packet ;
2018-04-03 23:17:43 -03:00
bool override_active = false ;
2012-08-16 21:50:03 -03:00
mavlink_msg_rc_channels_override_decode ( msg , & packet ) ;
2018-04-03 23:17:43 -03:00
override_active | = RC_Channels : : set_override ( 0 , packet . chan1_raw ) ;
override_active | = RC_Channels : : set_override ( 1 , packet . chan2_raw ) ;
override_active | = RC_Channels : : set_override ( 2 , packet . chan3_raw ) ;
override_active | = RC_Channels : : set_override ( 3 , packet . chan4_raw ) ;
override_active | = RC_Channels : : set_override ( 4 , packet . chan5_raw ) ;
override_active | = RC_Channels : : set_override ( 5 , packet . chan6_raw ) ;
override_active | = RC_Channels : : set_override ( 6 , packet . chan7_raw ) ;
override_active | = RC_Channels : : set_override ( 7 , packet . chan8_raw ) ;
2013-04-29 09:30:22 -03:00
// record that rc are overwritten so we can trigger a failsafe if we lose contact with groundstation
2018-04-03 23:17:43 -03:00
copter . failsafe . rc_override_active = override_active ;
2015-07-22 04:53:31 -03:00
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes
2015-11-19 23:04:45 -04:00
copter . failsafe . last_heartbeat_ms = AP_HAL : : millis ( ) ;
2012-08-16 21:50:03 -03:00
break ;
2017-03-18 22:04:36 -03:00
}
case MAVLINK_MSG_ID_MANUAL_CONTROL :
{
2018-04-03 20:20:31 -03:00
if ( msg - > sysid ! = copter . g . sysid_my_gcs ) {
break ; // only accept control from our gcs
}
2017-03-18 22:04:36 -03:00
mavlink_manual_control_t packet ;
mavlink_msg_manual_control_decode ( msg , & packet ) ;
2018-04-03 20:20:31 -03:00
if ( packet . target ! = copter . g . sysid_this_mav ) {
break ; // only accept control aimed at us
}
2017-03-18 22:04:36 -03:00
if ( packet . z < 0 ) { // Copter doesn't do negative thrust
break ;
}
bool override_active = false ;
int16_t roll = ( packet . y = = INT16_MAX ) ? 0 : copter . channel_roll - > get_radio_min ( ) + ( copter . channel_roll - > get_radio_max ( ) - copter . channel_roll - > get_radio_min ( ) ) * ( packet . y + 1000 ) / 2000.0f ;
int16_t pitch = ( packet . x = = INT16_MAX ) ? 0 : copter . channel_pitch - > get_radio_min ( ) + ( copter . channel_pitch - > get_radio_max ( ) - copter . channel_pitch - > get_radio_min ( ) ) * ( - packet . x + 1000 ) / 2000.0f ;
int16_t throttle = ( packet . z = = INT16_MAX ) ? 0 : copter . channel_throttle - > get_radio_min ( ) + ( copter . channel_throttle - > get_radio_max ( ) - copter . channel_throttle - > get_radio_min ( ) ) * ( packet . z ) / 1000.0f ;
int16_t yaw = ( packet . r = = INT16_MAX ) ? 0 : copter . channel_yaw - > get_radio_min ( ) + ( copter . channel_yaw - > get_radio_max ( ) - copter . channel_yaw - > get_radio_min ( ) ) * ( packet . r + 1000 ) / 2000.0f ;
2018-04-03 23:17:43 -03:00
override_active | = RC_Channels : : set_override ( uint8_t ( copter . rcmap . roll ( ) - 1 ) , roll ) ;
override_active | = RC_Channels : : set_override ( uint8_t ( copter . rcmap . pitch ( ) - 1 ) , pitch ) ;
override_active | = RC_Channels : : set_override ( uint8_t ( copter . rcmap . throttle ( ) - 1 ) , throttle ) ;
override_active | = RC_Channels : : set_override ( uint8_t ( copter . rcmap . yaw ( ) - 1 ) , yaw ) ;
2017-03-18 22:04:36 -03:00
// record that rc are overwritten so we can trigger a failsafe if we lose contact with groundstation
copter . failsafe . rc_override_active = override_active ;
// a manual control message is considered to be a 'heartbeat' from the ground station for failsafe purposes
copter . failsafe . last_heartbeat_ms = AP_HAL : : millis ( ) ;
break ;
2012-08-16 21:50:03 -03:00
}
2012-06-26 02:19:51 -03:00
2016-02-02 16:40:22 -04:00
case MAVLINK_MSG_ID_COMMAND_INT :
{
// decode packet
mavlink_command_int_t packet ;
mavlink_msg_command_int_decode ( msg , & packet ) ;
switch ( packet . command )
{
2018-01-25 08:36:03 -04:00
case MAV_CMD_DO_FOLLOW :
2018-02-06 02:16:09 -04:00
# if MODE_FOLLOW_ENABLED == ENABLED
2018-01-25 08:36:03 -04:00
// param1: sysid of target to follow
if ( ( packet . param1 > 0 ) & & ( packet . param1 < = 255 ) ) {
copter . g2 . follow . set_target_sysid ( ( uint8_t ) packet . param1 ) ;
result = MAV_RESULT_ACCEPTED ;
}
2018-02-06 02:16:09 -04:00
# endif
2018-01-25 08:36:03 -04:00
break ;
2017-09-19 01:32:38 -03:00
case MAV_CMD_DO_SET_HOME : {
// assume failure
result = MAV_RESULT_FAILED ;
if ( is_equal ( packet . param1 , 1.0f ) ) {
// if param1 is 1, use current location
if ( copter . set_home_to_current_location ( true ) ) {
result = MAV_RESULT_ACCEPTED ;
}
break ;
}
// ensure param1 is zero
if ( ! is_zero ( packet . param1 ) ) {
break ;
}
// check frame type is supported
if ( packet . frame ! = MAV_FRAME_GLOBAL & &
packet . frame ! = MAV_FRAME_GLOBAL_INT & &
packet . frame ! = MAV_FRAME_GLOBAL_RELATIVE_ALT & &
packet . frame ! = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT ) {
break ;
}
// sanity check location
if ( ! check_latlng ( packet . x , packet . y ) ) {
break ;
}
Location new_home_loc { } ;
new_home_loc . lat = packet . x ;
new_home_loc . lng = packet . y ;
new_home_loc . alt = packet . z * 100 ;
// handle relative altitude
if ( packet . frame = = MAV_FRAME_GLOBAL_RELATIVE_ALT | | packet . frame = = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT ) {
2018-03-15 22:23:28 -03:00
if ( ! AP : : ahrs ( ) . home_is_set ( ) ) {
2017-09-19 01:32:38 -03:00
// cannot use relative altitude if home is not set
break ;
}
new_home_loc . alt + = copter . ahrs . get_home ( ) . alt ;
}
if ( copter . set_home ( new_home_loc , true ) ) {
result = MAV_RESULT_ACCEPTED ;
}
break ;
}
2016-02-02 16:40:22 -04:00
case MAV_CMD_DO_SET_ROI : {
// param1 : /* Region of interest mode (not used)*/
// param2 : /* MISSION index/ target ID (not used)*/
// param3 : /* ROI index (not used)*/
// param4 : /* empty */
// x : lat
// y : lon
// z : alt
// sanity check location
2016-06-01 19:29:40 -03:00
if ( ! check_latlng ( packet . x , packet . y ) ) {
2016-02-02 16:40:22 -04:00
break ;
}
Location roi_loc ;
roi_loc . lat = packet . x ;
roi_loc . lng = packet . y ;
roi_loc . alt = ( int32_t ) ( packet . z * 100.0f ) ;
copter . set_auto_yaw_roi ( roi_loc ) ;
result = MAV_RESULT_ACCEPTED ;
break ;
}
2017-09-19 01:32:38 -03:00
2016-02-02 16:40:22 -04:00
default :
result = MAV_RESULT_UNSUPPORTED ;
break ;
}
// send ACK or NAK
mavlink_msg_command_ack_send_buf ( msg , chan , packet . command , result ) ;
break ;
}
2014-02-27 21:24:47 -04:00
// Pre-Flight calibration requests
case MAVLINK_MSG_ID_COMMAND_LONG : // MAV ID: 76
{
// decode packet
mavlink_command_long_t packet ;
mavlink_msg_command_long_decode ( msg , & packet ) ;
switch ( packet . command ) {
2015-04-30 03:06:55 -03:00
case MAV_CMD_NAV_TAKEOFF : {
2015-04-30 01:46:20 -03:00
// param3 : horizontal navigation by pilot acceptable
2014-08-04 11:10:36 -03:00
// param4 : yaw angle (not supported)
// param5 : latitude (not supported)
// param6 : longitude (not supported)
// param7 : altitude [metres]
2015-04-30 03:06:55 -03:00
float takeoff_alt = packet . param7 * 100 ; // Convert m to cm
2015-05-29 23:12:49 -03:00
if ( copter . do_user_takeoff ( takeoff_alt , is_zero ( packet . param3 ) ) ) {
2014-08-04 11:10:36 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
}
break ;
2015-04-30 03:06:55 -03:00
}
2014-08-04 11:10:36 -03:00
2014-02-27 21:24:47 -04:00
case MAV_CMD_NAV_LOITER_UNLIM :
2016-01-25 19:40:41 -04:00
if ( copter . set_mode ( LOITER , MODE_REASON_GCS_COMMAND ) ) {
2014-02-27 21:24:47 -04:00
result = MAV_RESULT_ACCEPTED ;
}
break ;
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
2016-01-25 19:40:41 -04:00
if ( copter . set_mode ( RTL , MODE_REASON_GCS_COMMAND ) ) {
2014-02-27 21:24:47 -04:00
result = MAV_RESULT_ACCEPTED ;
}
break ;
case MAV_CMD_NAV_LAND :
2016-01-25 19:40:41 -04:00
if ( copter . set_mode ( LAND , MODE_REASON_GCS_COMMAND ) ) {
2014-02-27 21:24:47 -04:00
result = MAV_RESULT_ACCEPTED ;
}
break ;
2018-01-25 08:36:03 -04:00
case MAV_CMD_DO_FOLLOW :
2018-02-06 02:16:09 -04:00
# if MODE_FOLLOW_ENABLED == ENABLED
2018-01-25 08:36:03 -04:00
// param1: sysid of target to follow
if ( ( packet . param1 > 0 ) & & ( packet . param1 < = 255 ) ) {
copter . g2 . follow . set_target_sysid ( ( uint8_t ) packet . param1 ) ;
result = MAV_RESULT_ACCEPTED ;
}
2018-02-06 02:16:09 -04:00
# endif
2018-01-25 08:36:03 -04:00
break ;
2014-06-13 06:17:35 -03:00
case MAV_CMD_CONDITION_YAW :
// param1 : target angle [0-360]
// param2 : speed during change [deg per second]
2014-09-26 00:20:40 -03:00
// param3 : direction (-1:ccw, +1:cw)
2014-06-13 06:17:35 -03:00
// param4 : relative offset (1) or absolute angle (0)
if ( ( packet . param1 > = 0.0f ) & &
( packet . param1 < = 360.0f ) & &
2015-05-04 23:34:21 -03:00
( is_zero ( packet . param4 ) | | is_equal ( packet . param4 , 1.0f ) ) ) {
2017-07-11 02:04:58 -03:00
copter . set_auto_yaw_look_at_heading ( packet . param1 , packet . param2 , ( int8_t ) packet . param3 , is_positive ( packet . param4 ) ) ;
2014-06-13 06:17:35 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
}
break ;
2014-05-29 12:04:53 -03:00
case MAV_CMD_DO_CHANGE_SPEED :
// param1 : unused
// param2 : new speed in m/s
// param3 : unused
// param4 : unused
if ( packet . param2 > 0.0f ) {
2017-01-09 03:31:26 -04:00
copter . wp_nav - > set_speed_xy ( packet . param2 * 100.0f ) ;
2014-05-29 12:04:53 -03:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
}
break ;
2015-02-09 07:25:45 -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
2017-09-19 04:21:59 -03:00
if ( is_equal ( packet . param1 , 1.0f ) ) {
2017-06-05 05:03:50 -03:00
if ( copter . set_home_to_current_location ( true ) ) {
2015-02-09 07:25:45 -04:00
result = MAV_RESULT_ACCEPTED ;
}
} else {
2017-09-19 04:21:59 -03:00
// ensure param1 is zero
if ( ! is_zero ( packet . param1 ) ) {
break ;
}
2015-08-27 02:38:55 -03:00
// sanity check location
2016-06-01 19:29:40 -03:00
if ( ! check_latlng ( packet . param5 , packet . param6 ) ) {
2015-08-27 02:38:55 -03:00
break ;
}
2015-02-09 07:25:45 -04:00
Location new_home_loc ;
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 ) ;
2017-06-05 05:03:50 -03:00
if ( copter . set_home ( new_home_loc , true ) ) {
2017-04-19 04:17:56 -03:00
result = MAV_RESULT_ACCEPTED ;
2015-02-09 07:25:45 -04:00
}
}
break ;
2014-07-04 03:40:12 -03:00
case MAV_CMD_DO_SET_ROI :
// param1 : regional of interest mode (not supported)
// param2 : mission index/ target id (not supported)
// param3 : ROI index (not supported)
// param5 : x / lat
// param6 : y / lon
// param7 : z / alt
2015-08-27 02:38:55 -03:00
// sanity check location
2016-06-01 19:29:40 -03:00
if ( ! check_latlng ( packet . param5 , packet . param6 ) ) {
2015-08-27 02:38:55 -03:00
break ;
}
2014-07-04 03:40:12 -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 ) ;
2015-05-29 23:12:49 -03:00
copter . set_auto_yaw_roi ( roi_loc ) ;
2014-07-04 03:40:12 -03:00
result = MAV_RESULT_ACCEPTED ;
break ;
2015-08-13 02:32:59 -03:00
case MAV_CMD_DO_MOUNT_CONTROL :
2015-09-02 04:44:22 -03:00
# if MOUNT == ENABLED
2017-12-20 17:59:49 -04:00
if ( ! copter . camera_mount . has_pan_control ( ) ) {
copter . set_auto_yaw_look_at_heading ( ( float ) packet . param3 / 100.0f , 0.0f , 0 , 0 ) ;
}
2015-08-13 02:32:59 -03:00
copter . camera_mount . control ( packet . param1 , packet . param2 , packet . param3 , ( MAV_MOUNT_MODE ) packet . param7 ) ;
2016-04-22 08:23:13 -03:00
result = MAV_RESULT_ACCEPTED ;
2015-09-02 04:44:22 -03:00
# endif
2015-08-13 02:32:59 -03:00
break ;
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2014-02-27 21:24:47 -04:00
case MAV_CMD_MISSION_START :
2017-01-09 03:31:26 -04:00
if ( copter . motors - > armed ( ) & & copter . set_mode ( AUTO , MODE_REASON_GCS_COMMAND ) ) {
2015-05-29 23:12:49 -03:00
copter . set_auto_armed ( true ) ;
2015-08-28 06:40:19 -03:00
if ( copter . mission . state ( ) ! = AP_Mission : : MISSION_RUNNING ) {
copter . mission . start_or_resume ( ) ;
}
2014-02-27 21:24:47 -04:00
result = MAV_RESULT_ACCEPTED ;
}
break ;
2018-02-21 22:06:07 -04:00
# endif
2014-02-27 21:24:47 -04:00
case MAV_CMD_COMPONENT_ARM_DISARM :
2015-05-04 23:34:21 -03:00
if ( is_equal ( packet . param1 , 1.0f ) ) {
2015-01-30 04:56:22 -04:00
// attempt to arm and return success or failure
2015-05-29 23:12:49 -03:00
if ( copter . init_arm_motors ( true ) ) {
2015-01-30 04:56:22 -04:00
result = MAV_RESULT_ACCEPTED ;
2014-02-27 21:24:47 -04:00
}
2015-09-18 17:29:25 -03:00
} else if ( is_zero ( packet . param1 ) & & ( copter . ap . land_complete | | is_equal ( packet . param2 , 21196.0f ) ) ) {
2015-08-12 14:28:35 -03:00
// force disarming by setting param2 = 21196 is deprecated
2015-05-29 23:12:49 -03:00
copter . init_disarm_motors ( ) ;
2014-03-19 19:06:28 -03:00
result = MAV_RESULT_ACCEPTED ;
2015-02-14 01:27:47 -04:00
} else {
result = MAV_RESULT_UNSUPPORTED ;
2014-02-27 21:24:47 -04:00
}
break ;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN :
2015-05-04 23:34:21 -03:00
if ( is_equal ( packet . param1 , 1.0f ) | | is_equal ( packet . param1 , 3.0f ) ) {
2015-03-19 00:08:58 -03:00
AP_Notify : : flags . firmware_update = 1 ;
2018-02-11 20:23:32 -04:00
copter . notify . update ( ) ;
2015-03-05 04:34:50 -04:00
hal . scheduler - > delay ( 200 ) ;
2014-02-27 21:24:47 -04:00
// when packet.param1 == 3 we reboot to hold in bootloader
2015-05-04 23:34:21 -03:00
hal . scheduler - > reboot ( is_equal ( packet . param1 , 3.0f ) ) ;
2014-02-27 21:24:47 -04:00
result = MAV_RESULT_ACCEPTED ;
}
break ;
2014-04-27 04:17:05 -03:00
case MAV_CMD_DO_FENCE_ENABLE :
# if AC_FENCE == ENABLED
result = MAV_RESULT_ACCEPTED ;
switch ( ( uint16_t ) packet . param1 ) {
case 0 :
2015-05-29 23:12:49 -03:00
copter . fence . enable ( false ) ;
2014-04-27 04:17:05 -03:00
break ;
case 1 :
2015-05-29 23:12:49 -03:00
copter . fence . enable ( true ) ;
2014-04-27 04:17:05 -03:00
break ;
default :
result = MAV_RESULT_FAILED ;
break ;
}
# else
// if fence code is not included return failure
result = MAV_RESULT_FAILED ;
# endif
break ;
2014-09-17 09:00:27 -03:00
# if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE :
// configure or release parachute
result = MAV_RESULT_ACCEPTED ;
switch ( ( uint16_t ) packet . param1 ) {
case PARACHUTE_DISABLE :
2015-05-29 23:12:49 -03:00
copter . parachute . enabled ( false ) ;
copter . Log_Write_Event ( DATA_PARACHUTE_DISABLED ) ;
2014-09-17 09:00:27 -03:00
break ;
case PARACHUTE_ENABLE :
2015-05-29 23:12:49 -03:00
copter . parachute . enabled ( true ) ;
copter . Log_Write_Event ( DATA_PARACHUTE_ENABLED ) ;
2014-09-17 09:00:27 -03:00
break ;
case PARACHUTE_RELEASE :
// treat as a manual release which performs some additional check of altitude
2015-05-29 23:12:49 -03:00
copter . parachute_manual_release ( ) ;
2014-09-17 09:00:27 -03:00
break ;
default :
result = MAV_RESULT_FAILED ;
break ;
}
2015-06-08 00:25:59 -03:00
break ;
2014-09-17 09:00:27 -03:00
# endif
2014-04-28 04:27:27 -03:00
case MAV_CMD_DO_MOTOR_TEST :
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
// param3 : throttle (range depends upon param2)
// param4 : timeout (in seconds)
2017-06-14 08:00:39 -03:00
// param5 : num_motors (in sequence)
2017-06-15 00:17:19 -03:00
// param6 : compass learning (0: disabled, 1: enabled)
2017-06-14 08:00:39 -03:00
result = copter . mavlink_motor_test_start ( chan , ( uint8_t ) packet . param1 , ( uint8_t ) packet . param2 , ( uint16_t ) packet . param3 ,
packet . param4 , ( uint8_t ) packet . param5 ) ;
2014-04-28 04:27:27 -03:00
break ;
2016-10-29 08:01:29 -03:00
# if GRIPPER_ENABLED == ENABLED
2014-09-17 08:31:30 -03:00
case MAV_CMD_DO_GRIPPER :
// param1 : gripper number (ignored)
// param2 : action (0=release, 1=grab). See GRIPPER_ACTIONS enum.
2016-10-29 08:01:29 -03:00
if ( ! copter . g2 . gripper . enabled ( ) ) {
2014-09-17 08:31:30 -03:00
result = MAV_RESULT_FAILED ;
} else {
result = MAV_RESULT_ACCEPTED ;
switch ( ( uint8_t ) packet . param2 ) {
case GRIPPER_ACTION_RELEASE :
2016-10-29 08:01:29 -03:00
copter . g2 . gripper . release ( ) ;
2014-09-17 08:31:30 -03:00
break ;
case GRIPPER_ACTION_GRAB :
2016-10-29 08:01:29 -03:00
copter . g2 . gripper . grab ( ) ;
2014-09-17 08:31:30 -03:00
break ;
default :
result = MAV_RESULT_FAILED ;
break ;
}
}
break ;
# endif
2015-02-11 18:04:20 -04:00
2018-02-10 10:23:06 -04:00
# if WINCH_ENABLED == ENABLED
2017-10-04 23:21:23 -03:00
case MAV_CMD_DO_WINCH :
// param1 : winch number (ignored)
// param2 : action (0=relax, 1=relative length control, 2=rate control). See WINCH_ACTIONS enum.
if ( ! copter . g2 . winch . enabled ( ) ) {
result = MAV_RESULT_FAILED ;
} else {
result = MAV_RESULT_ACCEPTED ;
switch ( ( uint8_t ) packet . param2 ) {
case WINCH_RELAXED :
copter . g2 . winch . relax ( ) ;
copter . Log_Write_Event ( DATA_WINCH_RELAXED ) ;
break ;
case WINCH_RELATIVE_LENGTH_CONTROL : {
copter . g2 . winch . release_length ( packet . param3 , fabsf ( packet . param4 ) ) ;
copter . Log_Write_Event ( DATA_WINCH_LENGTH_CONTROL ) ;
break ;
}
case WINCH_RATE_CONTROL : {
2017-10-26 09:07:24 -03:00
if ( fabsf ( packet . param4 ) < = copter . g2 . winch . get_rate_max ( ) ) {
2017-10-04 23:21:23 -03:00
copter . g2 . winch . set_desired_rate ( packet . param4 ) ;
copter . Log_Write_Event ( DATA_WINCH_RATE_CONTROL ) ;
} else {
result = MAV_RESULT_FAILED ;
}
break ;
}
default :
result = MAV_RESULT_FAILED ;
break ;
}
}
break ;
2018-02-10 10:23:06 -04:00
# endif
2017-10-04 23:21:23 -03:00
2016-05-12 23:38:30 -03:00
/* Solo user presses Fly button */
2016-01-05 02:22:36 -04:00
case MAV_CMD_SOLO_BTN_FLY_CLICK : {
result = MAV_RESULT_ACCEPTED ;
if ( copter . failsafe . radio ) {
break ;
}
2016-05-12 23:38:30 -03:00
// set mode to Loiter or fall back to AltHold
if ( ! copter . set_mode ( LOITER , MODE_REASON_GCS_COMMAND ) ) {
copter . set_mode ( ALT_HOLD , MODE_REASON_GCS_COMMAND ) ;
2016-01-05 02:22:36 -04:00
}
break ;
}
2016-05-12 23:38:30 -03:00
/* Solo user holds down Fly button for a couple of seconds */
2016-01-05 02:22:36 -04:00
case MAV_CMD_SOLO_BTN_FLY_HOLD : {
result = MAV_RESULT_ACCEPTED ;
if ( copter . failsafe . radio ) {
break ;
}
2017-01-09 03:31:26 -04:00
if ( ! copter . motors - > armed ( ) ) {
2016-05-12 23:38:30 -03:00
// if disarmed, arm motors
2016-01-05 02:22:36 -04:00
copter . init_arm_motors ( true ) ;
} else if ( copter . ap . land_complete ) {
2016-05-12 23:38:30 -03:00
// if armed and landed, takeoff
if ( copter . set_mode ( LOITER , MODE_REASON_GCS_COMMAND ) ) {
2016-01-05 02:22:36 -04:00
copter . do_user_takeoff ( packet . param1 * 100 , true ) ;
}
} else {
2016-05-12 23:38:30 -03:00
// if flying, land
copter . set_mode ( LAND , MODE_REASON_GCS_COMMAND ) ;
2016-01-05 02:22:36 -04:00
}
break ;
}
2016-05-12 23:38:30 -03:00
/* Solo user presses pause button */
2016-01-05 02:22:36 -04:00
case MAV_CMD_SOLO_BTN_PAUSE_CLICK : {
result = MAV_RESULT_ACCEPTED ;
if ( copter . failsafe . radio ) {
break ;
}
2017-01-09 03:31:26 -04:00
if ( copter . motors - > armed ( ) ) {
2016-01-05 02:22:36 -04:00
if ( copter . ap . land_complete ) {
// if landed, disarm motors
copter . init_disarm_motors ( ) ;
} else {
// assume that shots modes are all done in guided.
// NOTE: this may need to change if we add a non-guided shot mode
2016-08-01 05:44:12 -03:00
bool shot_mode = ( ! is_zero ( packet . param1 ) & & ( copter . control_mode = = GUIDED | | copter . control_mode = = GUIDED_NOGPS ) ) ;
2016-01-05 02:22:36 -04:00
if ( ! shot_mode ) {
2018-02-23 01:40:29 -04:00
# if MODE_BRAKE_ENABLED == ENABLED
2016-05-12 23:38:30 -03:00
if ( copter . set_mode ( BRAKE , MODE_REASON_GCS_COMMAND ) ) {
2017-12-11 01:43:27 -04:00
copter . mode_brake . timeout_to_loiter_ms ( 2500 ) ;
2016-01-05 02:22:36 -04:00
} else {
2016-05-12 23:38:30 -03:00
copter . set_mode ( ALT_HOLD , MODE_REASON_GCS_COMMAND ) ;
2016-01-05 02:22:36 -04:00
}
2018-02-23 01:40:29 -04:00
# else
copter . set_mode ( ALT_HOLD , MODE_REASON_GCS_COMMAND ) ;
# endif
2016-01-05 02:22:36 -04:00
} else {
// SoloLink is expected to handle pause in shots
}
}
}
break ;
}
2016-11-12 05:50:01 -04:00
case MAV_CMD_ACCELCAL_VEHICLE_POS :
result = MAV_RESULT_FAILED ;
if ( copter . ins . get_acal ( ) - > gcs_vehicle_position ( packet . param1 ) ) {
result = MAV_RESULT_ACCEPTED ;
}
break ;
2014-02-27 21:24:47 -04:00
default :
2017-07-13 22:43:40 -03:00
result = handle_command_long_message ( packet ) ;
2014-02-27 21:24:47 -04:00
break ;
}
// send ACK or NAK
2014-03-18 18:54:05 -03:00
mavlink_msg_command_ack_send_buf ( msg , chan , packet . command , result ) ;
2014-02-27 21:24:47 -04:00
break ;
}
2018-02-23 00:09:07 -04:00
# if MODE_GUIDED_ENABLED == ENABLED
2015-10-08 08:13:53 -03:00
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET : // MAV ID: 82
{
// decode packet
mavlink_set_attitude_target_t packet ;
mavlink_msg_set_attitude_target_decode ( msg , & packet ) ;
2016-08-01 05:43:15 -03:00
// exit if vehicle is not in Guided mode or Auto-Guided mode
2018-02-21 21:49:47 -04:00
if ( ! copter . flightmode - > in_guided_mode ( ) ) {
2016-08-01 05:43:15 -03:00
break ;
}
2015-10-10 09:43:43 -03:00
// ensure type_mask specifies to use attitude and thrust
if ( ( packet . type_mask & ( ( 1 < < 7 ) | ( 1 < < 6 ) ) ) ! = 0 ) {
2015-10-08 08:13:53 -03:00
break ;
}
// convert thrust to climb rate
packet . thrust = constrain_float ( packet . thrust , 0.0f , 1.0f ) ;
float climb_rate_cms = 0.0f ;
if ( is_equal ( packet . thrust , 0.5f ) ) {
climb_rate_cms = 0.0f ;
} else if ( packet . thrust > 0.5f ) {
// climb at up to WPNAV_SPEED_UP
2017-01-09 03:31:26 -04:00
climb_rate_cms = ( packet . thrust - 0.5f ) * 2.0f * copter . wp_nav - > get_speed_up ( ) ;
2015-10-08 08:13:53 -03:00
} else {
// descend at up to WPNAV_SPEED_DN
2017-01-09 03:31:26 -04:00
climb_rate_cms = ( 0.5f - packet . thrust ) * 2.0f * - fabsf ( copter . wp_nav - > get_speed_down ( ) ) ;
2015-10-08 08:13:53 -03:00
}
2016-08-02 14:20:57 -03:00
// if the body_yaw_rate field is ignored, use the commanded yaw position
// otherwise use the commanded yaw rate
bool use_yaw_rate = false ;
if ( ( packet . type_mask & ( 1 < < 2 ) ) = = 0 ) {
use_yaw_rate = true ;
}
2017-12-11 01:43:27 -04:00
copter . mode_guided . set_angle ( Quaternion ( packet . q [ 0 ] , packet . q [ 1 ] , packet . q [ 2 ] , packet . q [ 3 ] ) ,
2016-08-09 00:10:13 -03:00
climb_rate_cms , use_yaw_rate , packet . body_yaw_rate ) ;
2016-08-02 14:20:57 -03:00
2015-10-08 08:13:53 -03:00
break ;
}
2014-10-13 08:31:40 -03:00
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED : // MAV ID: 84
{
// decode packet
mavlink_set_position_target_local_ned_t packet ;
mavlink_msg_set_position_target_local_ned_decode ( msg , & packet ) ;
2014-10-13 23:26:08 -03:00
// exit if vehicle is not in Guided mode or Auto-Guided mode
2018-02-21 21:49:47 -04:00
if ( ! copter . flightmode - > in_guided_mode ( ) ) {
2014-10-13 08:31:40 -03:00
break ;
}
2015-08-11 08:26:28 -03:00
// check for supported coordinate frames
if ( packet . coordinate_frame ! = MAV_FRAME_LOCAL_NED & &
packet . coordinate_frame ! = MAV_FRAME_LOCAL_OFFSET_NED & &
packet . coordinate_frame ! = MAV_FRAME_BODY_NED & &
packet . coordinate_frame ! = MAV_FRAME_BODY_OFFSET_NED ) {
break ;
}
2014-11-14 21:18:17 -04:00
bool pos_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ;
bool vel_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ;
bool acc_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ;
2017-06-22 12:20:14 -03:00
bool yaw_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE ;
bool yaw_rate_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE ;
2014-11-14 21:18:17 -04:00
/*
* for future use :
* bool force = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE ;
*/
2015-08-11 08:26:28 -03:00
// prepare position
Vector3f pos_vector ;
if ( ! pos_ignore ) {
// convert to cm
pos_vector = Vector3f ( packet . x * 100.0f , packet . y * 100.0f , - packet . z * 100.0f ) ;
// rotate to body-frame if necessary
if ( packet . coordinate_frame = = MAV_FRAME_BODY_NED | |
packet . coordinate_frame = = MAV_FRAME_BODY_OFFSET_NED ) {
copter . rotate_body_frame_to_NE ( pos_vector . x , pos_vector . y ) ;
}
// add body offset if necessary
if ( packet . coordinate_frame = = MAV_FRAME_LOCAL_OFFSET_NED | |
packet . coordinate_frame = = MAV_FRAME_BODY_NED | |
packet . coordinate_frame = = MAV_FRAME_BODY_OFFSET_NED ) {
pos_vector + = copter . inertial_nav . get_position ( ) ;
} else {
// convert from alt-above-home to alt-above-ekf-origin
pos_vector . z = copter . pv_alt_above_origin ( pos_vector . z ) ;
}
}
// prepare velocity
Vector3f vel_vector ;
if ( ! vel_ignore ) {
// convert to cm
vel_vector = Vector3f ( packet . vx * 100.0f , packet . vy * 100.0f , - packet . vz * 100.0f ) ;
// rotate to body-frame if necessary
if ( packet . coordinate_frame = = MAV_FRAME_BODY_NED | | packet . coordinate_frame = = MAV_FRAME_BODY_OFFSET_NED ) {
copter . rotate_body_frame_to_NE ( vel_vector . x , vel_vector . y ) ;
}
}
2017-07-11 02:06:18 -03:00
// prepare yaw
float yaw_cd = 0.0f ;
bool yaw_relative = false ;
float yaw_rate_cds = 0.0f ;
if ( ! yaw_ignore ) {
yaw_cd = ToDeg ( packet . yaw ) * 100.0f ;
yaw_relative = packet . coordinate_frame = = MAV_FRAME_BODY_NED | | packet . coordinate_frame = = MAV_FRAME_BODY_OFFSET_NED ;
}
if ( ! yaw_rate_ignore ) {
yaw_rate_cds = ToDeg ( packet . yaw_rate ) * 100.0f ;
}
2015-08-11 08:26:28 -03:00
// send request
2014-11-14 21:18:17 -04:00
if ( ! pos_ignore & & ! vel_ignore & & acc_ignore ) {
2017-12-11 01:43:27 -04:00
if ( copter . mode_guided . set_destination_posvel ( pos_vector , vel_vector , ! yaw_ignore , yaw_cd , ! yaw_rate_ignore , yaw_rate_cds , yaw_relative ) ) {
2017-11-29 06:19:42 -04:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
}
2014-11-14 21:18:17 -04:00
} else if ( pos_ignore & & ! vel_ignore & & acc_ignore ) {
2017-12-11 01:43:27 -04:00
copter . mode_guided . set_velocity ( vel_vector , ! yaw_ignore , yaw_cd , ! yaw_rate_ignore , yaw_rate_cds , yaw_relative ) ;
2017-11-23 10:53:11 -04:00
result = MAV_RESULT_ACCEPTED ;
2014-11-14 21:18:17 -04:00
} else if ( ! pos_ignore & & vel_ignore & & acc_ignore ) {
2017-12-11 01:43:27 -04:00
if ( copter . mode_guided . set_destination ( pos_vector , ! yaw_ignore , yaw_cd , ! yaw_rate_ignore , yaw_rate_cds , yaw_relative ) ) {
2017-11-23 10:53:11 -04:00
result = MAV_RESULT_ACCEPTED ;
} else {
2016-04-28 04:35:29 -03:00
result = MAV_RESULT_FAILED ;
}
2014-11-14 21:18:17 -04:00
} else {
result = MAV_RESULT_FAILED ;
}
2014-10-13 08:31:40 -03:00
break ;
}
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT : // MAV ID: 86
{
// decode packet
mavlink_set_position_target_global_int_t packet ;
mavlink_msg_set_position_target_global_int_decode ( msg , & packet ) ;
2014-10-13 23:26:08 -03:00
// exit if vehicle is not in Guided mode or Auto-Guided mode
2018-02-21 21:49:47 -04:00
if ( ! copter . flightmode - > in_guided_mode ( ) ) {
2014-10-13 08:31:40 -03:00
break ;
}
2015-08-11 15:07:07 -03:00
// check for supported coordinate frames
2017-09-18 23:57:19 -03:00
if ( packet . coordinate_frame ! = MAV_FRAME_GLOBAL & &
packet . coordinate_frame ! = MAV_FRAME_GLOBAL_INT & &
2016-01-27 23:25:40 -04:00
packet . coordinate_frame ! = MAV_FRAME_GLOBAL_RELATIVE_ALT & & // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT
2015-08-11 15:07:07 -03:00
packet . coordinate_frame ! = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT & &
2017-09-18 23:57:19 -03:00
packet . coordinate_frame ! = MAV_FRAME_GLOBAL_TERRAIN_ALT & &
2015-08-11 15:07:07 -03:00
packet . coordinate_frame ! = MAV_FRAME_GLOBAL_TERRAIN_ALT_INT ) {
break ;
}
2014-11-14 21:18:17 -04:00
bool pos_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ;
bool vel_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ;
bool acc_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ;
2017-06-22 12:20:14 -03:00
bool yaw_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE ;
bool yaw_rate_ignore = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE ;
2014-11-14 21:18:17 -04:00
/*
* for future use :
* bool force = packet . type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE ;
*/
2017-11-24 13:04:34 -04:00
Vector3f pos_neu_cm ; // position (North, East, Up coordinates) in centimeters
2014-11-14 21:18:17 -04:00
if ( ! pos_ignore ) {
2016-06-01 19:29:40 -03:00
// sanity check location
if ( ! check_latlng ( packet . lat_int , packet . lon_int ) ) {
result = MAV_RESULT_FAILED ;
break ;
}
2014-11-14 21:18:17 -04:00
Location loc ;
loc . lat = packet . lat_int ;
loc . lng = packet . lon_int ;
2014-11-18 16:08:06 -04:00
loc . alt = packet . alt * 100 ;
2014-11-14 21:18:17 -04:00
switch ( packet . coordinate_frame ) {
2016-01-27 23:25:40 -04:00
case MAV_FRAME_GLOBAL_RELATIVE_ALT : // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT
2014-11-14 21:18:17 -04:00
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT :
loc . flags . relative_alt = true ;
loc . flags . terrain_alt = false ;
break ;
2017-09-18 23:57:19 -03:00
case MAV_FRAME_GLOBAL_TERRAIN_ALT :
2014-11-14 21:18:17 -04:00
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT :
loc . flags . relative_alt = true ;
loc . flags . terrain_alt = true ;
break ;
2017-09-18 23:57:19 -03:00
case MAV_FRAME_GLOBAL :
2014-11-19 16:06:30 -04:00
case MAV_FRAME_GLOBAL_INT :
default :
2017-11-27 01:24:30 -04:00
// pv_location_to_vector does not support absolute altitudes.
// Convert the absolute altitude to a home-relative altitude before calling pv_location_to_vector
2016-01-11 17:29:06 -04:00
loc . alt - = copter . ahrs . get_home ( ) . alt ;
loc . flags . relative_alt = true ;
2014-11-19 16:06:30 -04:00
loc . flags . terrain_alt = false ;
break ;
2014-11-14 21:18:17 -04:00
}
2017-11-24 13:04:34 -04:00
pos_neu_cm = copter . pv_location_to_vector ( loc ) ;
2014-11-14 21:18:17 -04:00
}
2017-07-11 02:06:18 -03:00
// prepare yaw
float yaw_cd = 0.0f ;
bool yaw_relative = false ;
float yaw_rate_cds = 0.0f ;
if ( ! yaw_ignore ) {
yaw_cd = ToDeg ( packet . yaw ) * 100.0f ;
yaw_relative = packet . coordinate_frame = = MAV_FRAME_BODY_NED | | packet . coordinate_frame = = MAV_FRAME_BODY_OFFSET_NED ;
}
if ( ! yaw_rate_ignore ) {
yaw_rate_cds = ToDeg ( packet . yaw_rate ) * 100.0f ;
}
2014-11-14 21:18:17 -04:00
if ( ! pos_ignore & & ! vel_ignore & & acc_ignore ) {
2017-12-11 01:43:27 -04:00
if ( copter . mode_guided . set_destination_posvel ( pos_neu_cm , Vector3f ( packet . vx * 100.0f , packet . vy * 100.0f , - packet . vz * 100.0f ) , ! yaw_ignore , yaw_cd , ! yaw_rate_ignore , yaw_rate_cds , yaw_relative ) ) {
2017-11-29 06:19:42 -04:00
result = MAV_RESULT_ACCEPTED ;
} else {
result = MAV_RESULT_FAILED ;
}
2014-11-14 21:18:17 -04:00
} else if ( pos_ignore & & ! vel_ignore & & acc_ignore ) {
2017-12-11 01:43:27 -04:00
copter . mode_guided . set_velocity ( Vector3f ( packet . vx * 100.0f , packet . vy * 100.0f , - packet . vz * 100.0f ) , ! yaw_ignore , yaw_cd , ! yaw_rate_ignore , yaw_rate_cds , yaw_relative ) ;
2017-11-23 10:53:11 -04:00
result = MAV_RESULT_ACCEPTED ;
2014-11-14 21:18:17 -04:00
} else if ( ! pos_ignore & & vel_ignore & & acc_ignore ) {
2017-12-11 01:43:27 -04:00
if ( copter . mode_guided . set_destination ( pos_neu_cm , ! yaw_ignore , yaw_cd , ! yaw_rate_ignore , yaw_rate_cds , yaw_relative ) ) {
2017-11-23 10:53:11 -04:00
result = MAV_RESULT_ACCEPTED ;
} else {
2016-04-28 04:35:29 -03:00
result = MAV_RESULT_FAILED ;
}
2014-11-14 21:18:17 -04:00
} else {
result = MAV_RESULT_FAILED ;
}
2014-10-13 08:31:40 -03:00
break ;
}
2018-02-23 00:09:07 -04:00
# endif
2014-10-13 08:31:40 -03:00
2016-05-04 00:03:56 -03:00
case MAVLINK_MSG_ID_DISTANCE_SENSOR :
{
result = MAV_RESULT_ACCEPTED ;
2016-04-27 08:37:04 -03:00
copter . rangefinder . handle_msg ( msg ) ;
2017-01-09 23:09:39 -04:00
# if PROXIMITY_ENABLED == ENABLED
copter . g2 . proximity . handle_msg ( msg ) ;
# endif
2016-05-04 00:03:56 -03:00
break ;
}
2012-07-04 21:55:58 -03:00
# if HIL_MODE != HIL_MODE_DISABLED
2014-02-27 21:24:47 -04:00
case MAVLINK_MSG_ID_HIL_STATE : // MAV ID: 90
2012-08-16 21:50:03 -03:00
{
mavlink_hil_state_t packet ;
mavlink_msg_hil_state_decode ( msg , & packet ) ;
2012-06-26 02:19:51 -03:00
2016-06-01 19:29:40 -03:00
// sanity check location
if ( ! check_latlng ( packet . lat , packet . lon ) ) {
break ;
}
2012-08-16 21:50:03 -03:00
// set gps hil sensor
2014-03-31 04:07:46 -03:00
Location loc ;
loc . lat = packet . lat ;
loc . lng = packet . lon ;
loc . alt = packet . alt / 10 ;
Vector3f vel ( packet . vx , packet . vy , packet . vz ) ;
vel * = 0.01f ;
2014-04-01 17:51:19 -03:00
gps . setHIL ( 0 , AP_GPS : : GPS_OK_FIX_3D ,
2014-03-31 04:07:46 -03:00
packet . time_usec / 1000 ,
2016-05-04 22:42:28 -03:00
loc , vel , 10 , 0 ) ;
2012-06-26 02:19:51 -03:00
2012-08-16 21:50:03 -03:00
// rad/sec
Vector3f gyros ;
gyros . x = packet . rollspeed ;
gyros . y = packet . pitchspeed ;
gyros . z = packet . yawspeed ;
2013-03-19 03:07:15 -03:00
2012-08-16 21:50:03 -03:00
// m/s/s
Vector3f accels ;
2015-05-02 06:26:19 -03:00
accels . x = packet . xacc * ( GRAVITY_MSS / 1000.0f ) ;
accels . y = packet . yacc * ( GRAVITY_MSS / 1000.0f ) ;
accels . z = packet . zacc * ( GRAVITY_MSS / 1000.0f ) ;
2012-06-04 05:24:08 -03:00
2014-02-22 17:18:20 -04:00
ins . set_gyro ( 0 , gyros ) ;
2012-06-04 05:24:08 -03:00
2014-02-22 17:18:20 -04:00
ins . set_accel ( 0 , accels ) ;
2012-06-26 02:19:51 -03:00
2018-03-05 16:37:25 -04:00
AP : : baro ( ) . setHIL ( packet . alt * 0.001f ) ;
2015-05-29 23:12:49 -03:00
copter . compass . setHIL ( 0 , packet . roll , packet . pitch , packet . yaw ) ;
copter . compass . setHIL ( 1 , packet . roll , packet . pitch , packet . yaw ) ;
2012-06-04 05:24:08 -03:00
2012-08-16 21:50:03 -03:00
break ;
}
2012-07-04 21:55:58 -03:00
# endif // HIL_MODE != HIL_MODE_DISABLED
2012-06-26 02:19:51 -03:00
2014-02-27 21:24:47 -04:00
case MAVLINK_MSG_ID_RADIO :
case MAVLINK_MSG_ID_RADIO_STATUS : // MAV ID: 109
2013-04-29 09:30:22 -03:00
{
2015-05-29 23:12:49 -03:00
handle_radio_status ( msg , copter . DataFlash , copter . should_log ( MASK_LOG_PM ) ) ;
2013-04-29 09:30:22 -03:00
break ;
}
2012-04-01 22:18:42 -03:00
2015-09-10 16:06:38 -03:00
# if PRECISION_LANDING == ENABLED
2016-03-20 14:12:31 -03:00
case MAVLINK_MSG_ID_LANDING_TARGET :
result = MAV_RESULT_ACCEPTED ;
copter . precland . handle_msg ( msg ) ;
break ;
2015-09-10 16:06:38 -03:00
# endif
2016-06-23 03:24:58 -03:00
# if AC_FENCE == ENABLED
// send or receive fence points with GCS
case MAVLINK_MSG_ID_FENCE_POINT : // MAV ID: 160
case MAVLINK_MSG_ID_FENCE_FETCH_POINT :
2017-07-09 05:31:50 -03:00
copter . fence . handle_msg ( * this , msg ) ;
2016-06-23 03:24:58 -03:00
break ;
# endif // AC_FENCE == ENABLED
2012-07-24 23:02:54 -03:00
# if MOUNT == ENABLED
2015-08-13 02:32:59 -03:00
//deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
2014-02-27 21:24:47 -04:00
case MAVLINK_MSG_ID_MOUNT_CONFIGURE : // MAV ID: 204
2015-05-29 23:12:49 -03:00
copter . camera_mount . configure_msg ( msg ) ;
2012-08-16 21:50:03 -03:00
break ;
2015-08-13 02:32:59 -03:00
//deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
2012-07-24 23:02:54 -03:00
case MAVLINK_MSG_ID_MOUNT_CONTROL :
2017-12-20 17:59:49 -04:00
if ( ! copter . camera_mount . has_pan_control ( ) ) {
copter . set_auto_yaw_look_at_heading ( mavlink_msg_mount_control_get_input_c ( msg ) / 100.0f , 0.0f , 0 , 0 ) ;
}
2015-05-29 23:12:49 -03:00
copter . camera_mount . control_msg ( msg ) ;
2012-08-16 21:50:03 -03:00
break ;
2012-07-24 23:02:54 -03:00
# endif // MOUNT == ENABLED
2014-04-06 22:18:43 -03:00
2014-07-22 05:22:36 -03:00
case MAVLINK_MSG_ID_TERRAIN_DATA :
case MAVLINK_MSG_ID_TERRAIN_CHECK :
2015-11-13 23:38:47 -04:00
# if AP_TERRAIN_AVAILABLE && AC_TERRAIN
2015-05-29 23:12:49 -03:00
copter . terrain . handle_data ( chan , msg ) ;
2014-07-22 05:22:36 -03:00
# endif
break ;
2015-10-02 22:37:02 -03:00
case MAVLINK_MSG_ID_SET_HOME_POSITION :
{
mavlink_set_home_position_t packet ;
mavlink_msg_set_home_position_decode ( msg , & packet ) ;
if ( ( packet . latitude = = 0 ) & & ( packet . longitude = = 0 ) & & ( packet . altitude = = 0 ) ) {
2017-06-05 05:03:50 -03:00
copter . set_home_to_current_location ( true ) ;
2015-10-02 22:37:02 -03:00
} else {
// sanity check location
2016-06-01 19:29:40 -03:00
if ( ! check_latlng ( packet . latitude , packet . longitude ) ) {
2015-10-02 22:37:02 -03:00
break ;
}
Location new_home_loc ;
new_home_loc . lat = packet . latitude ;
new_home_loc . lng = packet . longitude ;
2016-04-15 16:28:29 -03:00
new_home_loc . alt = packet . altitude / 10 ;
2017-06-05 05:03:50 -03:00
copter . set_home ( new_home_loc , true ) ;
2015-10-02 22:37:02 -03:00
}
break ;
}
2015-11-25 19:22:21 -04:00
case MAVLINK_MSG_ID_ADSB_VEHICLE :
2016-08-16 20:19:48 -03:00
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG :
case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC :
2016-08-16 19:37:29 -03:00
case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT :
2016-07-10 21:21:57 -03:00
# if ADSB_ENABLED == ENABLED
2016-08-16 20:19:48 -03:00
copter . adsb . handle_message ( chan , msg ) ;
2016-07-10 21:21:57 -03:00
# endif
break ;
2018-01-18 02:49:20 -04:00
# if TOY_MODE_ENABLED == ENABLED
case MAVLINK_MSG_ID_NAMED_VALUE_INT :
copter . g2 . toy_mode . handle_message ( msg ) ;
break ;
# endif
2016-11-06 20:06:51 -04:00
default :
handle_common_message ( msg ) ;
2016-01-20 22:50:49 -04:00
break ;
2014-02-27 21:24:47 -04:00
} // end switch
} // end handle mavlink
2012-07-24 23:02:54 -03:00
2013-03-20 23:54:04 -03:00
2011-08-01 05:08:52 -03:00
/*
2012-08-16 21:50:03 -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-29 23:12:49 -03:00
void Copter : : mavlink_delay_cb ( )
2011-08-01 05:08:52 -03:00
{
2012-05-22 03:08:46 -03:00
static uint32_t last_1hz , last_50hz , last_5s ;
2017-02-13 22:14:55 -04:00
if ( ! gcs ( ) . chan ( 0 ) . initialised | | in_mavlink_delay ) return ;
2011-09-04 21:15:36 -03:00
2012-08-16 21:50:03 -03:00
in_mavlink_delay = true ;
2017-06-14 22:48:02 -03:00
DataFlash . EnableWrites ( false ) ;
2011-08-01 05:08:52 -03:00
2012-12-12 21:25:09 -04:00
uint32_t tnow = millis ( ) ;
if ( tnow - last_1hz > 1000 ) {
last_1hz = tnow ;
2013-01-08 01:45:12 -04:00
gcs_send_heartbeat ( ) ;
2017-07-07 22:43:24 -03:00
gcs ( ) . send_message ( MSG_EXTENDED_STATUS1 ) ;
2012-12-12 21:25:09 -04:00
}
if ( tnow - last_50hz > 20 ) {
last_50hz = tnow ;
2013-01-08 01:45:12 -04:00
gcs_check_input ( ) ;
2012-12-12 21:25:09 -04:00
gcs_data_stream_send ( ) ;
2013-01-08 01:45:12 -04:00
gcs_send_deferred ( ) ;
2013-08-29 00:14:07 -03:00
notify . update ( ) ;
2012-12-12 21:25:09 -04:00
}
if ( tnow - last_5s > 5000 ) {
last_5s = tnow ;
2017-07-08 21:56:49 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Initialising APM " ) ;
2012-12-12 21:25:09 -04:00
}
check_usb_mux ( ) ;
2011-09-04 21:15:36 -03:00
2017-06-14 22:48:02 -03:00
DataFlash . EnableWrites ( true ) ;
2012-08-16 21:50:03 -03:00
in_mavlink_delay = false ;
2011-08-23 03:16:37 -03:00
}
2011-10-11 06:12:37 -03:00
/*
2012-08-16 21:50:03 -03:00
* send data streams in the given rate range on both links
2011-10-11 06:12:37 -03:00
*/
2015-05-29 23:12:49 -03:00
void Copter : : gcs_data_stream_send ( void )
2011-10-11 06:12:37 -03:00
{
2017-02-13 22:14:55 -04:00
gcs ( ) . data_stream_send ( ) ;
2011-11-20 05:42:51 -04:00
}
2011-10-11 06:12:37 -03:00
/*
2012-08-16 21:50:03 -03:00
* look for incoming commands on the GCS links
2011-10-11 06:12:37 -03:00
*/
2015-05-29 23:12:49 -03:00
void Copter : : gcs_check_input ( void )
2011-10-11 06:12:37 -03:00
{
2017-02-13 22:14:55 -04:00
gcs ( ) . update ( ) ;
2011-11-20 05:42:51 -04:00
}
2011-10-11 06:12:37 -03:00
2016-08-19 01:36:47 -03:00
/*
return true if we will accept this packet . Used to implement SYSID_ENFORCE
*/
bool GCS_MAVLINK_Copter : : accept_packet ( const mavlink_status_t & status , mavlink_message_t & msg )
{
if ( ! copter . g2 . sysid_enforce ) {
return true ;
}
if ( msg . msgid = = MAVLINK_MSG_ID_RADIO | | msg . msgid = = MAVLINK_MSG_ID_RADIO_STATUS ) {
return true ;
}
return ( msg . sysid = = copter . g . sysid_my_gcs ) ;
}
2017-07-07 23:51:10 -03:00
AP_Mission * GCS_MAVLINK_Copter : : get_mission ( )
{
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2017-07-07 23:51:10 -03:00
return & copter . mission ;
2018-02-21 22:06:07 -04:00
# else
return nullptr ;
# endif
2017-07-07 23:51:10 -03:00
}
2017-07-12 21:20:57 -03:00
2017-07-16 21:47:24 -03:00
Compass * GCS_MAVLINK_Copter : : get_compass ( ) const
{
return & copter . compass ;
}
2017-07-26 03:10:42 -03:00
AP_Camera * GCS_MAVLINK_Copter : : get_camera ( ) const
{
# if CAMERA == ENABLED
return & copter . camera ;
# else
return nullptr ;
# endif
}
2017-07-13 23:45:51 -03:00
AP_ServoRelayEvents * GCS_MAVLINK_Copter : : get_servorelayevents ( ) const
{
return & copter . ServoRelayEvents ;
}
2017-07-25 03:36:17 -03:00
AP_AdvancedFailsafe * GCS_MAVLINK_Copter : : get_advanced_failsafe ( ) const
{
# if ADVANCED_FAILSAFE == ENABLED
return & copter . g2 . afs ;
# else
return nullptr ;
# endif
}
2018-03-07 18:52:48 -04:00
AP_VisualOdom * GCS_MAVLINK_Copter : : get_visual_odom ( ) const
{
# if VISUAL_ODOMETRY_ENABLED == ENABLED
return & copter . g2 . visual_odom ;
# else
return nullptr ;
# endif
}
2017-07-25 03:36:17 -03:00
MAV_RESULT GCS_MAVLINK_Copter : : handle_flight_termination ( const mavlink_command_long_t & packet ) {
MAV_RESULT result = MAV_RESULT_FAILED ;
# if ADVANCED_FAILSAFE == ENABLED
if ( GCS_MAVLINK : : handle_flight_termination ( packet ) ! = MAV_RESULT_ACCEPTED ) {
# endif
if ( packet . param1 > 0.5f ) {
copter . init_disarm_motors ( ) ;
result = MAV_RESULT_ACCEPTED ;
}
# if ADVANCED_FAILSAFE == ENABLED
} else {
result = MAV_RESULT_ACCEPTED ;
}
# endif
return result ;
}
2017-07-12 21:20:57 -03:00
AP_Rally * GCS_MAVLINK_Copter : : get_rally ( ) const
{
# if AC_RALLY == ENABLED
return & copter . rally ;
# else
return nullptr ;
# endif
}
2017-08-11 03:02:52 -03:00
bool GCS_MAVLINK_Copter : : set_mode ( const uint8_t mode )
{
# ifdef DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE
if ( copter . failsafe . radio ) {
// don't allow mode changes while in radio failsafe
return false ;
}
# endif
return copter . set_mode ( ( control_mode_t ) mode , MODE_REASON_GCS_COMMAND ) ;
}
2017-08-18 19:46:48 -03:00
const AP_FWVersion & GCS_MAVLINK_Copter : : get_fwver ( ) const
{
return copter . fwver ;
}
2017-09-18 23:36:05 -03:00
void GCS_MAVLINK_Copter : : set_ekf_origin ( const Location & loc )
{
copter . set_ekf_origin ( loc ) ;
}