mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-08 22:53:57 -04:00
AP_Motors: display message in heli parameter_check()
This commit is contained in:
parent
94eb23ef56
commit
f22a1d3e6d
libraries/AP_Motors
@ -22,6 +22,7 @@
|
|||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include "AP_MotorsHeli.h"
|
#include "AP_MotorsHeli.h"
|
||||||
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -272,25 +273,37 @@ void AP_MotorsHeli::output_disarmed()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// parameter_check - check if helicopter specific parameters are sensible
|
// parameter_check - check if helicopter specific parameters are sensible
|
||||||
bool AP_MotorsHeli::parameter_check() const
|
bool AP_MotorsHeli::parameter_check(bool display_msg) const
|
||||||
{
|
{
|
||||||
// returns false if _rsc_setpoint is not higher than _rsc_critical as this would not allow rotor_runup_complete to ever return true
|
// returns false if _rsc_setpoint is not higher than _rsc_critical as this would not allow rotor_runup_complete to ever return true
|
||||||
if (_rsc_critical >= _rsc_setpoint) {
|
if (_rsc_critical >= _rsc_setpoint) {
|
||||||
|
if (display_msg) {
|
||||||
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: H_RSC_CRITICAL too large"));
|
||||||
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// returns false if RSC Mode is not set to a valid control mode
|
// returns false if RSC Mode is not set to a valid control mode
|
||||||
if (_rsc_mode <= (int8_t)ROTOR_CONTROL_MODE_DISABLED || _rsc_mode > (int8_t)ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
|
if (_rsc_mode <= (int8_t)ROTOR_CONTROL_MODE_DISABLED || _rsc_mode > (int8_t)ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
|
||||||
|
if (display_msg) {
|
||||||
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: H_RSC_MODE invalid"));
|
||||||
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// returns false if RSC Runup Time is less than Ramp time as this could cause undesired behaviour of rotor speed estimate
|
// returns false if RSC Runup Time is less than Ramp time as this could cause undesired behaviour of rotor speed estimate
|
||||||
if (_rsc_runup_time <= _rsc_ramp_time){
|
if (_rsc_runup_time <= _rsc_ramp_time){
|
||||||
|
if (display_msg) {
|
||||||
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: H_RUNUP_TIME too small"));
|
||||||
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// returns false if idle output is higher than critical rotor speed as this could block runup_complete from going false
|
// returns false if idle output is higher than critical rotor speed as this could block runup_complete from going false
|
||||||
if ( _rsc_idle_output >= _rsc_critical){
|
if ( _rsc_idle_output >= _rsc_critical){
|
||||||
|
if (display_msg) {
|
||||||
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: H_RSC_IDLE too large"));
|
||||||
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -102,7 +102,7 @@ public:
|
|||||||
virtual bool allow_arming() const = 0;
|
virtual bool allow_arming() const = 0;
|
||||||
|
|
||||||
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
// parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check
|
||||||
bool parameter_check() const;
|
bool parameter_check(bool display_msg) const;
|
||||||
|
|
||||||
// has_flybar - returns true if we have a mechical flybar
|
// has_flybar - returns true if we have a mechical flybar
|
||||||
virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; }
|
virtual bool has_flybar() const { return AP_MOTORS_HELI_NOFLYBAR; }
|
||||||
|
Loading…
Reference in New Issue
Block a user