mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: make AUTO_TRIGGER_PIN be a push on/push off
This commit is contained in:
parent
8361cd31f2
commit
b58d753344
@ -138,7 +138,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
|
|
||||||
// @Param: AUTO_TRIGGER_PIN
|
// @Param: AUTO_TRIGGER_PIN
|
||||||
// @DisplayName: Auto mode trigger pin
|
// @DisplayName: Auto mode trigger pin
|
||||||
// @Description: pin number to use to trigger start of auto mode. If set to -1 then don't use a trigger, otherwise this is a pin number which if held low in auto mode will start the motor.
|
// @Description: pin number to use to trigger start of auto mode. If set to -1 then don't use a trigger, otherwise this is a pin number which if held low in auto mode will start the motor, and otherwise will force the throttle off. This can be used in combination with INITIAL_MODE to give a 'press button to start' rover with no receiver.
|
||||||
// @Values: -1:Disabled,0-9:TiggerPin
|
// @Values: -1:Disabled,0-9:TiggerPin
|
||||||
// @User: standard
|
// @User: standard
|
||||||
GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),
|
GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),
|
||||||
|
@ -27,6 +27,13 @@ static bool auto_check_trigger(void)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check for user pressing the auto trigger to off
|
||||||
|
if (auto_triggered && g.auto_trigger_pin != -1 && check_digital_pin(g.auto_trigger_pin) == 1) {
|
||||||
|
gcs_send_text_P(SEVERITY_LOW, PSTR("AUTO triggered off"));
|
||||||
|
auto_triggered = false;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// if already triggered, then return true, so you don't
|
// if already triggered, then return true, so you don't
|
||||||
// need to hold the switch down
|
// need to hold the switch down
|
||||||
if (auto_triggered) {
|
if (auto_triggered) {
|
||||||
@ -39,21 +46,10 @@ static bool auto_check_trigger(void)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (g.auto_trigger_pin != -1) {
|
if (g.auto_trigger_pin != -1 && check_digital_pin(g.auto_trigger_pin) == 0) {
|
||||||
int8_t pin = hal.gpio->analogPinToDigitalPin(g.auto_trigger_pin);
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Triggered AUTO with pin"));
|
||||||
if (pin != -1) {
|
auto_triggered = true;
|
||||||
// ensure we are in input mode
|
return true;
|
||||||
hal.gpio->pinMode(pin, GPIO_INPUT);
|
|
||||||
|
|
||||||
// enable pullup
|
|
||||||
hal.gpio->write(pin, 1);
|
|
||||||
|
|
||||||
if (hal.gpio->read(pin) == 0) {
|
|
||||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Triggered AUTO with pin"));
|
|
||||||
auto_triggered = true;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (g.auto_kickstart != 0.0f) {
|
if (g.auto_kickstart != 0.0f) {
|
||||||
|
@ -545,3 +545,21 @@ static void reboot_apm(void)
|
|||||||
hal.scheduler->reboot();
|
hal.scheduler->reboot();
|
||||||
while (1);
|
while (1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
check a digitial pin for high,low (1/0)
|
||||||
|
*/
|
||||||
|
static uint8_t check_digital_pin(uint8_t pin)
|
||||||
|
{
|
||||||
|
int8_t dpin = hal.gpio->analogPinToDigitalPin(pin);
|
||||||
|
if (dpin == -1) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
// ensure we are in input mode
|
||||||
|
hal.gpio->pinMode(dpin, GPIO_INPUT);
|
||||||
|
|
||||||
|
// enable pullup
|
||||||
|
hal.gpio->write(dpin, 1);
|
||||||
|
|
||||||
|
return hal.gpio->read(dpin);
|
||||||
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user