2015-06-04 00:13:34 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
additional arming checks for plane
*/
# include "Plane.h"
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_Arming_Plane : : var_info [ ] = {
2015-08-24 00:53:15 -03:00
// variables from parent vehicle
AP_NESTEDGROUPINFO ( AP_Arming , 0 ) ,
// @Param: RUDDER
// @DisplayName: Rudder Arming
// @Description: Control arm/disarm by rudder input. When enabled arming is done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero
// @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm
// @User: Advanced
AP_GROUPINFO ( " RUDDER " , 3 , AP_Arming_Plane , rudder_arming_value , ARMING_RUDDER_ARMONLY ) ,
AP_GROUPEND
} ;
2015-06-04 00:13:34 -03:00
/*
additional arming checks for plane
*/
bool AP_Arming_Plane : : pre_arm_checks ( bool report )
{
// call parent class checks
bool ret = AP_Arming : : pre_arm_checks ( report ) ;
2015-08-24 00:53:15 -03:00
// Check airspeed sensor
ret & = AP_Arming : : airspeed_checks ( report ) ;
2015-06-04 00:13:34 -03:00
if ( plane . g . roll_limit_cd < 300 ) {
if ( report ) {
2015-10-24 18:45:41 -03:00
GCS_MAVLINK : : send_statustext_all ( MAV_SEVERITY_CRITICAL , " PreArm: LIM_ROLL_CD too small (%u) " , plane . g . roll_limit_cd ) ;
2015-06-04 00:13:34 -03:00
}
ret = false ;
}
if ( plane . aparm . pitch_limit_max_cd < 300 ) {
if ( report ) {
2015-10-24 18:45:41 -03:00
GCS_MAVLINK : : send_statustext_all ( MAV_SEVERITY_CRITICAL , " PreArm: LIM_PITCH_MAX too small (%u) " , plane . aparm . pitch_limit_max_cd ) ;
2015-06-04 00:13:34 -03:00
}
ret = false ;
}
if ( plane . aparm . pitch_limit_min_cd > - 300 ) {
if ( report ) {
2015-10-24 18:45:41 -03:00
GCS_MAVLINK : : send_statustext_all ( MAV_SEVERITY_CRITICAL , " PreArm: LIM_PITCH_MIN too large (%u) " , plane . aparm . pitch_limit_min_cd ) ;
2015-06-04 00:13:34 -03:00
}
ret = false ;
}
if ( plane . channel_throttle - > get_reverse ( ) & &
plane . g . throttle_fs_enabled & &
plane . g . throttle_fs_value <
plane . channel_throttle - > radio_max ) {
if ( report ) {
2015-11-18 15:17:50 -04:00
GCS_MAVLINK : : send_statustext_all ( MAV_SEVERITY_CRITICAL , " PreArm: Invalid THR_FS_VALUE for rev throttle " ) ;
2015-06-04 00:13:34 -03:00
}
ret = false ;
}
return ret ;
}
2015-10-16 00:52:57 -03:00
bool AP_Arming_Plane : : ins_checks ( bool report )
{
// call parent class checks
if ( ! AP_Arming : : ins_checks ( report ) ) {
return false ;
}
// additional plane specific checks
if ( ( checks_to_perform & ARMING_CHECK_ALL ) | |
( checks_to_perform & ARMING_CHECK_INS ) ) {
if ( ! ahrs . healthy ( ) ) {
if ( report ) {
const char * reason = ahrs . prearm_failure_reason ( ) ;
if ( reason ) {
2015-10-24 18:45:41 -03:00
GCS_MAVLINK : : send_statustext_all ( MAV_SEVERITY_CRITICAL , " PreArm: %s " , reason ) ;
2015-10-16 00:52:57 -03:00
} else {
2015-10-24 18:45:41 -03:00
GCS_MAVLINK : : send_statustext_all ( MAV_SEVERITY_CRITICAL , " PreArm: AHRS not healthy " ) ;
2015-10-16 00:52:57 -03:00
}
}
return false ;
}
}
return true ;
}