Plane: added plane specific arming checks

added check for roll and pitch limits, after flyaway due to small
LIM_ROLL_CD
This commit is contained in:
Andrew Tridgell 2015-06-04 13:13:34 +10:00
parent 2de8c26c06
commit 5942bf5cf0
2 changed files with 64 additions and 1 deletions

View File

@ -104,10 +104,26 @@
#include <AP_HAL_Empty.h>
#include <AP_HAL_VRBRAIN.h>
/*
a plane specific arming class
*/
class AP_Arming_Plane : public AP_Arming
{
public:
AP_Arming_Plane(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const enum HomeState &home_set, gcs_send_t_p gcs_send) :
AP_Arming(ahrs_ref, baro, compass, home_set, gcs_send) {}
bool pre_arm_checks(bool report);
};
/*
main APM:Plane class
*/
class Plane {
public:
friend class GCS_MAVLINK;
friend class Parameters;
friend class AP_Arming_Plane;
Plane(void);
void setup();
@ -610,7 +626,7 @@ private:
#endif
// Arming/Disarming mangement class
AP_Arming arming {ahrs, barometer, compass, home_is_set,
AP_Arming_Plane arming {ahrs, barometer, compass, home_is_set,
FUNCTOR_BIND_MEMBER(&Plane::gcs_send_text_P, void, gcs_severity, const prog_char_t *)};
AP_Param param_loader {var_info};

View File

@ -0,0 +1,47 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
additional arming checks for plane
*/
#include "Plane.h"
/*
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);
if (plane.g.roll_limit_cd < 300) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: LIM_ROLL_CD too small"));
}
ret = false;
}
if (plane.aparm.pitch_limit_max_cd < 300) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: LIM_PITCH_MAX too small"));
}
ret = false;
}
if (plane.aparm.pitch_limit_min_cd > -300) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: LIM_PITCH_MIN too large"));
}
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) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: invalid THR_FS_VALUE for rev throttle"));
}
ret = false;
}
return ret;
}