mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AR_Motors: remove arming check to allow ackerman and skid-steering
This commit is contained in:
parent
0665f9c32b
commit
adac463154
@ -454,16 +454,6 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm)
|
|||||||
// returns true if checks pass, false if they fail. report should be true to send text messages to GCS
|
// returns true if checks pass, false if they fail. report should be true to send text messages to GCS
|
||||||
bool AP_MotorsUGV::pre_arm_check(bool report) const
|
bool AP_MotorsUGV::pre_arm_check(bool report) const
|
||||||
{
|
{
|
||||||
// check if both regular and skid steering functions have been defined
|
|
||||||
if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) &&
|
|
||||||
SRV_Channels::function_assigned(SRV_Channel::k_throttleRight) &&
|
|
||||||
SRV_Channels::function_assigned(SRV_Channel::k_throttle) &&
|
|
||||||
SRV_Channels::function_assigned(SRV_Channel::k_steering)) {
|
|
||||||
if (report) {
|
|
||||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: regular AND skid steering configured");
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
// check if only one of skid-steering output has been configured
|
// check if only one of skid-steering output has been configured
|
||||||
if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) != SRV_Channels::function_assigned(SRV_Channel::k_throttleRight)) {
|
if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) != SRV_Channels::function_assigned(SRV_Channel::k_throttleRight)) {
|
||||||
if (report) {
|
if (report) {
|
||||||
|
Loading…
Reference in New Issue
Block a user