mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_MotorsHeli: Add more parameter checks.
This commit is contained in:
parent
652283a570
commit
3a13db9333
@ -98,7 +98,7 @@ public:
|
||||
//
|
||||
|
||||
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
||||
bool parameter_check(bool display_msg) const;
|
||||
virtual bool parameter_check(bool display_msg) const;
|
||||
|
||||
// has_flybar - returns true if we have a mechical flybar
|
||||
virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; }
|
||||
|
@ -18,6 +18,7 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include "AP_MotorsHeli_Single.h"
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -534,3 +535,34 @@ void AP_MotorsHeli_Single::servo_test()
|
||||
_pitch_control_input = _pitch_test;
|
||||
_yaw_control_input = _yaw_test;
|
||||
}
|
||||
|
||||
// parameter_check - check if helicopter specific parameters are sensible
|
||||
bool AP_MotorsHeli_Single::parameter_check(bool display_msg) const
|
||||
{
|
||||
// returns false if Phase Angle is outside of range
|
||||
if ((_phase_angle > 90) || (_phase_angle < -90)){
|
||||
if (display_msg) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: H_PHANG out of range");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// returns false if Acro External Gyro Gain is outside of range
|
||||
if ((_ext_gyro_gain_acro < 0) || (_ext_gyro_gain_acro > 1000)){
|
||||
if (display_msg) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN_ACRO out of range");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// returns false if Standard External Gyro Gain is outside of range
|
||||
if ((_ext_gyro_gain_std < 0) || (_ext_gyro_gain_std > 1000)){
|
||||
if (display_msg) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN out of range");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// check parent class parameters
|
||||
return AP_MotorsHeli::parameter_check(display_msg);
|
||||
}
|
||||
|
@ -126,6 +126,9 @@ public:
|
||||
|
||||
// servo_test - move servos through full range of movement
|
||||
void servo_test();
|
||||
|
||||
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
||||
bool parameter_check(bool display_msg) const;
|
||||
|
||||
// var_info
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
Loading…
Reference in New Issue
Block a user