首先我没有做过ArduRover,以下仅仅从代码进行推断,你可以试试,告诉我结果。首先上代码/*
check for driver input on rudder/steering stick for arming/disarming
*/
void Rover::rudder_arm_disarm_check()
{
...
首先我没有做过ArduRover,以下仅仅从代码进行推断,你可以试试,告诉我结果。首先上代码/*
check for driver input on rudder/steering stick for arming/disarming
*/
void Rover::rudder_arm_disarm_check()
{
// check if arming/disarm using rudder is allowed
const AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
return;
}
// In Rover we need to check that its set to the throttle trim and within the DZ
// if throttle is not within trim dz, then pilot cannot rudder arm/disarm
if (!channel_throttle->in_trim_dz()) {
rudder_arm_timer = 0;
return;
}
// check if arming/disarming allowed from this mode
if (!control_mode->allows_arming_from_transmitter()) {
rudder_arm_timer = 0;
return;
}
if (!arming.is_armed()) {
// when not armed, full right rudder starts arming counter
if (channel_steer->get_control_in() > 4000) {
const uint32_t now = millis();
if (rudder_arm_timer == 0 ||
now - rudder_arm_timer < ARM_DELAY_MS) {
if (rudder_arm_timer == 0) {
rudder_arm_timer = now;
}
} else {
// time to arm!
arming.arm(AP_Arming::Method::RUDDER);
rudder_arm_timer = 0;
}
} else {
// not at full right rudder
rudder_arm_timer = 0;
}
} else if ((arming_rudder == AP_Arming::RudderArming::ARMDISARM) && !g2.motors.active()) {
// when armed and motor not active (not moving), full left rudder starts disarming counter
if (channel_steer->get_control_in() < -4000) {
const uint32_t now = millis();
if (rudder_arm_timer == 0 ||
now - rudder_arm_timer < ARM_DELAY_MS) {
if (rudder_arm_timer == 0) {
rudder_arm_timer = now;
}
} else {
// time to disarm!
arming.disarm(AP_Arming::Method::RUDDER);
rudder_arm_timer = 0;
}
} else {
// not at full left rudder
rudder_arm_timer = 0;
}
}
}