mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Arming: formatting changes
This commit is contained in:
parent
6f36267a66
commit
6b91beb3ff
@ -41,14 +41,14 @@ const AP_Param::GroupInfo AP_Arming::var_info[] PROGMEM = {
|
|||||||
//The function point is particularly hacky, hacky, tacky
|
//The function point is particularly hacky, hacky, tacky
|
||||||
//but I don't want to reimplement messaging to GCS at the moment:
|
//but I don't want to reimplement messaging to GCS at the moment:
|
||||||
AP_Arming::AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
AP_Arming::AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
||||||
const enum HomeState &home_set)
|
const enum HomeState &home_set) :
|
||||||
: armed(false)
|
ahrs(ahrs_ref),
|
||||||
, logging_available(false)
|
barometer(baro),
|
||||||
, arming_method(NONE)
|
_compass(compass),
|
||||||
, ahrs(ahrs_ref)
|
home_is_set(home_set),
|
||||||
, barometer(baro)
|
armed(false),
|
||||||
, _compass(compass)
|
logging_available(false),
|
||||||
, home_is_set(home_set)
|
arming_method(NONE)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
memset(last_accel_pass_ms, 0, sizeof(last_accel_pass_ms));
|
memset(last_accel_pass_ms, 0, sizeof(last_accel_pass_ms));
|
||||||
@ -65,7 +65,8 @@ uint16_t AP_Arming::get_enabled_checks()
|
|||||||
return checks_to_perform;
|
return checks_to_perform;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Arming::set_enabled_checks(uint16_t ap) {
|
void AP_Arming::set_enabled_checks(uint16_t ap)
|
||||||
|
{
|
||||||
checks_to_perform = ap;
|
checks_to_perform = ap;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -73,7 +74,7 @@ bool AP_Arming::barometer_checks(bool report)
|
|||||||
{
|
{
|
||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
(checks_to_perform & ARMING_CHECK_BARO)) {
|
(checks_to_perform & ARMING_CHECK_BARO)) {
|
||||||
if (! barometer.healthy()) {
|
if (!barometer.healthy()) {
|
||||||
if (report) {
|
if (report) {
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Barometer not healthy!"));
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Barometer not healthy!"));
|
||||||
}
|
}
|
||||||
@ -123,7 +124,7 @@ bool AP_Arming::ins_checks(bool report)
|
|||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
(checks_to_perform & ARMING_CHECK_INS)) {
|
(checks_to_perform & ARMING_CHECK_INS)) {
|
||||||
const AP_InertialSensor &ins = ahrs.get_ins();
|
const AP_InertialSensor &ins = ahrs.get_ins();
|
||||||
if (! ins.get_gyro_health_all()) {
|
if (!ins.get_gyro_health_all()) {
|
||||||
if (report) {
|
if (report) {
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: gyros not healthy!"));
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: gyros not healthy!"));
|
||||||
}
|
}
|
||||||
@ -135,7 +136,7 @@ bool AP_Arming::ins_checks(bool report)
|
|||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (! ins.get_accel_health_all()) {
|
if (!ins.get_accel_health_all()) {
|
||||||
if (report) {
|
if (report) {
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: accels not healthy!"));
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: accels not healthy!"));
|
||||||
}
|
}
|
||||||
@ -240,7 +241,7 @@ bool AP_Arming::compass_checks(bool report)
|
|||||||
}
|
}
|
||||||
|
|
||||||
//check if compass is calibrating
|
//check if compass is calibrating
|
||||||
if(_compass.is_calibrating()) {
|
if (_compass.is_calibrating()) {
|
||||||
if (report) {
|
if (report) {
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Arm: Compass calibration running"));
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("Arm: Compass calibration running"));
|
||||||
}
|
}
|
||||||
@ -248,7 +249,7 @@ bool AP_Arming::compass_checks(bool report)
|
|||||||
}
|
}
|
||||||
|
|
||||||
//check if compass has calibrated and requires reboot
|
//check if compass has calibrated and requires reboot
|
||||||
if(_compass.compass_cal_requires_reboot()) {
|
if (_compass.compass_cal_requires_reboot()) {
|
||||||
if (report) {
|
if (report) {
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Compass calibrated requires reboot"));
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Compass calibrated requires reboot"));
|
||||||
}
|
}
|
||||||
@ -310,7 +311,7 @@ bool AP_Arming::battery_checks(bool report)
|
|||||||
|
|
||||||
if (AP_Notify::flags.failsafe_battery) {
|
if (AP_Notify::flags.failsafe_battery) {
|
||||||
if (report) {
|
if (report) {
|
||||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Battery failsafe on."));
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: Battery failsafe on"));
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@ -408,7 +409,7 @@ bool AP_Arming::arm(uint8_t method)
|
|||||||
//returns true if disarming occurred successfully
|
//returns true if disarming occurred successfully
|
||||||
bool AP_Arming::disarm()
|
bool AP_Arming::disarm()
|
||||||
{
|
{
|
||||||
if (! armed) { // already disarmed
|
if (!armed) { // already disarmed
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
armed = false;
|
armed = false;
|
||||||
@ -425,4 +426,3 @@ AP_Arming::ArmingRequired AP_Arming::arming_required()
|
|||||||
{
|
{
|
||||||
return (AP_Arming::ArmingRequired)require.get();
|
return (AP_Arming::ArmingRequired)require.get();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -61,28 +61,26 @@ public:
|
|||||||
|
|
||||||
void set_logging_available(bool set) { logging_available = set; }
|
void set_logging_available(bool set) { logging_available = set; }
|
||||||
|
|
||||||
//for params
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
bool armed:1;
|
// Parameters
|
||||||
bool logging_available:1;
|
AP_Int8 require;
|
||||||
|
AP_Int8 rudder_arming_value;
|
||||||
|
AP_Int16 checks_to_perform; // bitmask for which checks are required
|
||||||
|
|
||||||
//Parameters
|
// references
|
||||||
AP_Int8 require;
|
const AP_AHRS &ahrs;
|
||||||
AP_Int8 rudder_arming_value;
|
const AP_Baro &barometer;
|
||||||
//bitmask for which checks are required
|
Compass &_compass;
|
||||||
AP_Int16 checks_to_perform;
|
const enum HomeState &home_is_set;
|
||||||
|
|
||||||
//how the vehicle was armed
|
// internal members
|
||||||
uint8_t arming_method;
|
bool armed:1;
|
||||||
|
bool logging_available:1;
|
||||||
const AP_AHRS &ahrs;
|
uint8_t arming_method; // how the vehicle was armed
|
||||||
const AP_Baro &barometer;
|
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
|
||||||
Compass &_compass;
|
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
|
||||||
const enum HomeState &home_is_set;
|
|
||||||
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
|
|
||||||
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
|
|
||||||
|
|
||||||
void set_enabled_checks(uint16_t);
|
void set_enabled_checks(uint16_t);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user