AP_Motors: use GCS_SEND_TEXT
This commit is contained in:
parent
d33cc2847d
commit
5de4ac4258
@ -266,7 +266,7 @@ void AP_MotorsMatrix_6DoF_Scripting::add_motor(int8_t motor_num, float roll_fact
|
|||||||
|
|
||||||
uint8_t chan;
|
uint8_t chan;
|
||||||
if (!SRV_Channels::find_channel(function, chan)) {
|
if (!SRV_Channels::find_channel(function, chan)) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num);
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user