2015-05-13 03:09:36 -03:00
# include "Plane.h"
2015-08-28 03:01:32 -03:00
# include <AP_RSSI/AP_RSSI.h>
2015-05-13 03:09:36 -03:00
2016-05-23 22:31:53 -03:00
void Plane : : init_barometer ( bool full_calibration )
2011-09-08 22:29:39 -03:00
{
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Calibrating barometer " ) ;
2016-05-23 22:31:53 -03:00
if ( full_calibration ) {
barometer . calibrate ( ) ;
} else {
barometer . update_calibration ( ) ;
}
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Barometer calibration complete " ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : init_rangefinder ( void )
2013-10-30 19:23:21 -03:00
{
2014-08-26 08:17:47 -03:00
rangefinder . init ( ) ;
2013-10-30 19:23:21 -03:00
}
2014-08-26 08:17:47 -03:00
/*
read the rangefinder and update height estimate
*/
2015-05-13 03:09:36 -03:00
void Plane : : read_rangefinder ( void )
2013-10-30 19:23:21 -03:00
{
2015-10-15 18:50:06 -03:00
// notify the rangefinder of our approximate altitude above ground to allow it to power on
// during low-altitude flight when configured to power down during higher-altitude flight
float height ;
# if AP_TERRAIN_AVAILABLE
if ( terrain . status ( ) = = AP_Terrain : : TerrainStatusOK & & terrain . height_above_terrain ( height , true ) ) {
rangefinder . set_estimated_terrain_height ( height ) ;
} else
# endif
{
// use the best available alt estimate via baro above home
2017-01-11 01:29:03 -04:00
if ( flight_stage = = AP_Vehicle : : FixedWing : : FLIGHT_LAND ) {
2015-10-15 18:50:06 -03:00
// ensure the rangefinder is powered-on when land alt is higher than home altitude.
// This is done using the target alt which we know is below us and we are sinking to it
height = height_above_target ( ) ;
} else {
// otherwise just use the best available baro estimate above home.
2017-01-30 15:48:22 -04:00
height = relative_altitude ;
2015-10-15 18:50:06 -03:00
}
rangefinder . set_estimated_terrain_height ( height ) ;
}
2014-08-26 08:17:47 -03:00
rangefinder . update ( ) ;
2017-10-11 03:50:16 -03:00
if ( ( rangefinder . num_sensors ( ) > 0 ) & & should_log ( MASK_LOG_SONAR ) ) {
2013-10-30 19:23:21 -03:00
Log_Write_Sonar ( ) ;
2017-10-11 03:50:16 -03:00
}
2014-08-26 22:50:07 -03:00
rangefinder_height_update ( ) ;
2013-10-30 19:23:21 -03:00
}
2015-07-31 00:21:50 -03:00
/*
calibrate compass
*/
void Plane : : compass_cal_update ( ) {
if ( ! hal . util - > get_soft_armed ( ) ) {
compass . compass_cal_update ( ) ;
}
}
2015-10-21 18:11:52 -03:00
/*
Accel calibration
*/
void Plane : : accel_cal_update ( ) {
if ( hal . util - > get_soft_armed ( ) ) {
return ;
}
ins . acal_update ( ) ;
float trim_roll , trim_pitch ;
if ( ins . get_new_trim ( trim_roll , trim_pitch ) ) {
ahrs . set_trim ( Vector3f ( trim_roll , trim_pitch , 0 ) ) ;
}
}
2013-08-28 09:37:07 -03:00
/*
ask airspeed sensor for a new value
*/
2015-05-13 03:09:36 -03:00
void Plane : : read_airspeed ( void )
2011-09-08 22:29:39 -03:00
{
2013-06-04 00:34:58 -03:00
if ( airspeed . enabled ( ) ) {
airspeed . read ( ) ;
2014-01-27 19:35:59 -04:00
if ( should_log ( MASK_LOG_IMU ) ) {
Log_Write_Airspeed ( ) ;
}
2014-11-11 20:26:49 -04:00
// supply a new temperature to the barometer from the digital
// airspeed sensor if we can
float temperature ;
if ( airspeed . get_temperature ( temperature ) ) {
barometer . set_external_temperature ( temperature ) ;
}
2013-06-04 00:34:58 -03:00
}
2014-11-11 22:35:34 -04:00
2017-07-31 06:58:19 -03:00
// we calculate airspeed errors (and thus target_airspeed_cm) even
// when airspeed is disabled as TECS may be using synthetic
// airspeed for a quadplane transition
calc_airspeed_errors ( ) ;
2014-11-11 22:35:34 -04:00
// update smoothed airspeed estimate
float aspeed ;
if ( ahrs . airspeed_estimate ( & aspeed ) ) {
smoothed_airspeed = smoothed_airspeed * 0.8f + aspeed * 0.2f ;
}
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : zero_airspeed ( bool in_startup )
2011-09-08 22:29:39 -03:00
{
2014-11-13 06:12:59 -04:00
airspeed . calibrate ( in_startup ) ;
2014-11-11 20:26:49 -04:00
read_airspeed ( ) ;
// update barometric calibration with new airspeed supplied temperature
barometer . update_calibration ( ) ;
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Airspeed calibration started " ) ;
2011-09-08 22:29:39 -03:00
}
2013-09-29 09:54:39 -03:00
// read_battery - reads battery voltage and current and invokes failsafe
// should be called at 10hz
2015-05-13 03:09:36 -03:00
void Plane : : read_battery ( void )
2011-09-08 22:29:39 -03:00
{
2013-09-29 09:54:39 -03:00
battery . read ( ) ;
2014-04-14 19:28:32 -03:00
compass . set_current ( battery . current_amps ( ) ) ;
2012-08-16 21:50:15 -03:00
2017-02-07 01:49:33 -04:00
if ( hal . util - > get_soft_armed ( ) & &
2015-08-13 23:41:19 -03:00
battery . exhausted ( g . fs_batt_voltage , g . fs_batt_mah ) ) {
2013-05-22 07:33:57 -03:00
low_battery_event ( ) ;
}
2016-11-19 20:28:04 -04:00
if ( battery . get_type ( ) ! = AP_BattMonitor : : BattMonitor_TYPE_NONE ) {
2017-01-20 01:37:07 -04:00
AP_Notify : : flags . battery_voltage = battery . voltage ( ) ;
2016-11-19 20:28:04 -04:00
}
2016-02-29 06:24:33 -04:00
if ( should_log ( MASK_LOG_CURRENT ) ) {
Log_Write_Current ( ) ;
}
2011-09-08 22:29:39 -03:00
}
2012-08-22 00:58:25 -03:00
// read the receiver RSSI as an 8 bit number for MAVLink
2012-08-22 00:33:12 -03:00
// RC_CHANNELS_SCALED message
2015-05-13 03:09:36 -03:00
void Plane : : read_receiver_rssi ( void )
2012-08-22 00:33:12 -03:00
{
2015-08-28 03:01:32 -03:00
receiver_rssi = rssi . read_receiver_rssi_uint8 ( ) ;
2012-08-22 00:33:12 -03:00
}
2012-09-19 03:22:53 -03:00
2015-09-24 07:58:18 -03:00
/*
update RPM sensors
*/
void Plane : : rpm_update ( void )
{
rpm_sensor . update ( ) ;
2017-02-21 08:20:01 -04:00
if ( rpm_sensor . enabled ( 0 ) | | rpm_sensor . enabled ( 1 ) ) {
2015-09-24 07:58:18 -03:00
if ( should_log ( MASK_LOG_RC ) ) {
DataFlash . Log_Write_RPM ( rpm_sensor ) ;
}
}
}
2016-07-21 21:28:17 -03:00
/*
update AP_Button
*/
void Plane : : button_update ( void )
{
g2 . button . update ( ) ;
}
2016-07-23 04:37:42 -03:00
/*
update AP_ICEngine
*/
void Plane : : ice_update ( void )
{
g2 . ice_control . update ( ) ;
}
2016-10-27 23:09:35 -03:00
// update error mask of sensors and subsystems. The mask
// uses the MAV_SYS_STATUS_* values from mavlink. If a bit is set
// then it indicates that the sensor or subsystem is present but
// not functioning correctly.
void Plane : : update_sensor_status_flags ( void )
{
// default sensors present
control_sensors_present = MAVLINK_SENSOR_PRESENT_DEFAULT ;
// first what sensors/controllers we have
if ( g . compass_enabled ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_3D_MAG ; // compass present
}
if ( airspeed . enabled ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ;
}
if ( gps . status ( ) > AP_GPS : : NO_GPS ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_GPS ;
}
# if OPTFLOW == ENABLED
if ( optflow . enabled ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW ;
}
# endif
if ( geofence_present ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_GEOFENCE ;
}
if ( aparm . throttle_min < 0 ) {
control_sensors_present | = MAV_SYS_STATUS_REVERSE_MOTOR ;
}
if ( plane . DataFlash . logging_present ( ) ) { // primary logging only (usually File)
control_sensors_present | = MAV_SYS_STATUS_LOGGING ;
}
2017-01-17 00:10:37 -04:00
if ( plane . battery . healthy ( ) ) {
control_sensors_present | = MAV_SYS_STATUS_SENSOR_BATTERY ;
}
// all present sensors enabled by default except rate control, attitude stabilization, yaw, altitude, position control, geofence, motor, and battery 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 & ~ MAV_SYS_STATUS_LOGGING & ~ MAV_SYS_STATUS_SENSOR_BATTERY ) ;
2016-10-27 23:09:35 -03:00
if ( airspeed . enabled ( ) & & airspeed . use ( ) ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ;
}
if ( geofence_enabled ( ) ) {
control_sensors_enabled | = MAV_SYS_STATUS_GEOFENCE ;
}
if ( plane . DataFlash . logging_enabled ( ) ) {
control_sensors_enabled | = MAV_SYS_STATUS_LOGGING ;
}
2017-01-17 00:10:37 -04:00
if ( g . fs_batt_voltage > 0 | | g . fs_batt_mah > 0 ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_BATTERY ;
}
2016-10-27 23:09:35 -03:00
switch ( control_mode ) {
case MANUAL :
break ;
case ACRO :
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL ; // 3D angular rate control
break ;
case STABILIZE :
case FLY_BY_WIRE_A :
case AUTOTUNE :
case QSTABILIZE :
case QHOVER :
case QLAND :
case QLOITER :
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
break ;
case FLY_BY_WIRE_B :
case CRUISE :
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
break ;
case TRAINING :
if ( ! training_manual_roll | | ! training_manual_pitch ) {
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
}
break ;
case AUTO :
case RTL :
case LOITER :
case AVOID_ADSB :
case GUIDED :
case CIRCLE :
case QRTL :
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
break ;
case INITIALISING :
break ;
}
// 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 ;
}
// 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 |
MAV_SYS_STATUS_SENSOR_GPS |
MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ) ;
control_sensors_health | = MAV_SYS_STATUS_GEOFENCE ;
if ( ahrs . initialised ( ) & & ! ahrs . healthy ( ) ) {
// AHRS subsystem is unhealthy
control_sensors_health & = ~ MAV_SYS_STATUS_AHRS ;
}
if ( ahrs . have_inertial_nav ( ) & & ! ins . accel_calibrated_ok_all ( ) ) {
// trying to use EKF without properly calibrated accelerometers
control_sensors_health & = ~ MAV_SYS_STATUS_AHRS ;
}
if ( barometer . all_healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE ;
}
2017-09-07 01:19:26 -03:00
if ( g . compass_enabled & & compass . healthy ( ) & & ahrs . use_compass ( ) ) {
2016-10-27 23:09:35 -03:00
control_sensors_health | = MAV_SYS_STATUS_SENSOR_3D_MAG ;
}
2017-09-21 22:41:09 -03:00
if ( gps . status ( ) > = AP_GPS : : GPS_OK_FIX_3D & & gps . is_healthy ( ) ) {
2016-10-27 23:09:35 -03:00
control_sensors_health | = MAV_SYS_STATUS_SENSOR_GPS ;
}
# if OPTFLOW == ENABLED
if ( optflow . healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW ;
}
# endif
if ( ! ins . get_gyro_health_all ( ) | | ! ins . gyro_calibrated_ok_all ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_3D_GYRO ;
}
if ( ! ins . get_accel_health_all ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_3D_ACCEL ;
}
if ( airspeed . healthy ( ) ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE ;
}
# if GEOFENCE_ENABLED
if ( geofence_breached ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_GEOFENCE ;
}
# endif
if ( plane . DataFlash . logging_failed ( ) ) {
control_sensors_health & = ~ MAV_SYS_STATUS_LOGGING ;
}
if ( millis ( ) - failsafe . last_valid_rc_ms < 200 ) {
control_sensors_health | = MAV_SYS_STATUS_SENSOR_RC_RECEIVER ;
} else {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_RC_RECEIVER ;
}
# if AP_TERRAIN_AVAILABLE
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
2017-02-09 07:39:58 -04:00
if ( rangefinder . has_orientation ( ROTATION_PITCH_270 ) ) {
2016-10-27 23:09:35 -03:00
control_sensors_present | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
if ( g . rangefinder_landing ) {
control_sensors_enabled | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
}
2017-02-09 07:39:58 -04:00
if ( rangefinder . has_data_orient ( ROTATION_PITCH_270 ) ) {
2016-10-27 23:09:35 -03:00
control_sensors_health | = MAV_SYS_STATUS_SENSOR_LASER_POSITION ;
}
}
2016-10-22 07:27:57 -03:00
if ( aparm . throttle_min < 0 & & SRV_Channels : : get_output_scaled ( SRV_Channel : : k_throttle ) < 0 ) {
2016-10-27 23:09:35 -03:00
control_sensors_enabled | = MAV_SYS_STATUS_REVERSE_MOTOR ;
control_sensors_health | = MAV_SYS_STATUS_REVERSE_MOTOR ;
}
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 ) ;
}
2017-01-17 00:10:37 -04:00
if ( plane . failsafe . low_battery ) {
control_sensors_health & = ~ MAV_SYS_STATUS_SENSOR_BATTERY ;
}
2016-10-27 23:09:35 -03:00
# if FRSKY_TELEM_ENABLED == ENABLED
// give mask of error flags to Frsky_Telemetry
frsky_telemetry . update_sensor_status_flags ( ~ control_sensors_health & control_sensors_enabled & control_sensors_present ) ;
# endif
}