mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: eliminate GCS_MAVLINK::send_statustext_all
This commit is contained in:
parent
eab60e6163
commit
35d8f11e46
|
@ -35,7 +35,7 @@ void AP_MotorsCoax::init(motor_frame_class frame_class, motor_frame_type frame_t
|
|||
_servo3 = SRV_Channels::get_channel_for(SRV_Channel::k_motor3, CH_3);
|
||||
_servo4 = SRV_Channels::get_channel_for(SRV_Channel::k_motor4, CH_4);
|
||||
if (!_servo1 || !_servo2 || !_servo3 || !_servo4) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_ERROR, "MotorsCoax: unable to setup output channels");
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "MotorsCoax: unable to setup output channels");
|
||||
// don't set initialised_ok
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -336,7 +336,7 @@ 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
|
||||
if (_rsc_critical >= _rsc_setpoint) {
|
||||
if (display_msg) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_CRITICAL too large");
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_CRITICAL too large");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -344,7 +344,7 @@ bool AP_MotorsHeli::parameter_check(bool display_msg) const
|
|||
// 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 (display_msg) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_MODE invalid");
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_MODE invalid");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -352,7 +352,7 @@ bool AP_MotorsHeli::parameter_check(bool display_msg) const
|
|||
// 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 (display_msg) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: H_RUNUP_TIME too small");
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RUNUP_TIME too small");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -360,7 +360,7 @@ bool AP_MotorsHeli::parameter_check(bool display_msg) const
|
|||
// 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 (display_msg) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_IDLE too large");
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_IDLE too large");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -553,7 +553,7 @@ 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");
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_PHANG out of range");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -561,7 +561,7 @@ bool AP_MotorsHeli_Single::parameter_check(bool display_msg) const
|
|||
// 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");
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN_ACRO out of range");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -569,7 +569,7 @@ bool AP_MotorsHeli_Single::parameter_check(bool display_msg) const
|
|||
// 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");
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN out of range");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -42,7 +42,7 @@ void AP_MotorsSingle::init(motor_frame_class frame_class, motor_frame_type frame
|
|||
_servo3 = SRV_Channels::get_channel_for(SRV_Channel::k_motor3, CH_3);
|
||||
_servo4 = SRV_Channels::get_channel_for(SRV_Channel::k_motor4, CH_4);
|
||||
if (!_servo1 || !_servo2 || !_servo3 || !_servo4) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_ERROR, "MotorsSingle: unable to setup output channels");
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "MotorsSingle: unable to setup output channels");
|
||||
// don't set initialised_ok
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -43,7 +43,7 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty
|
|||
// find the yaw servo
|
||||
_yaw_servo = SRV_Channels::get_channel_for(SRV_Channel::k_motor7, AP_MOTORS_CH_TRI_YAW);
|
||||
if (!_yaw_servo) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_ERROR, "MotorsTri: unable to setup yaw channel");
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "MotorsTri: unable to setup yaw channel");
|
||||
// don't set initialised_ok
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue