mirror of https://github.com/ArduPilot/ardupilot
AP_LandingGear: use GCS_SEND_TEXT rather than gcs().send_text
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
9a1aece9ab
commit
52d5b4e684
|
@ -168,7 +168,7 @@ void AP_LandingGear::deploy()
|
|||
// send message only if output has been configured
|
||||
if (!_deployed &&
|
||||
SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: DEPLOY");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "LandingGear: DEPLOY");
|
||||
}
|
||||
|
||||
// set deployed flag
|
||||
|
@ -194,7 +194,7 @@ void AP_LandingGear::retract()
|
|||
|
||||
// send message only if output has been configured
|
||||
if (SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: RETRACT");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "LandingGear: RETRACT");
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue