Browse Source

AP_AdvancedFailsafe: add note to desc's on how to determine GPIO pin numbers

apm_2208
Henry Wurzburg 3 years ago committed by Randy Mackay
parent
commit
9d6f9bf907
  1. 6
      libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp

6
libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp

@ -42,13 +42,13 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
// @Param: MAN_PIN // @Param: MAN_PIN
// @DisplayName: Manual Pin // @DisplayName: Manual Pin
// @Description: This sets a digital output pin to set high when in manual mode // @Description: This sets a digital output pin to set high when in manual mode. See the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
// @User: Advanced // @User: Advanced
AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1), AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1),
// @Param: HB_PIN // @Param: HB_PIN
// @DisplayName: Heartbeat Pin // @DisplayName: Heartbeat Pin
// @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination. // @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
// @User: Advanced // @User: Advanced
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5 // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5
AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1), AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1),
@ -79,7 +79,7 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
// @Param: TERM_PIN // @Param: TERM_PIN
// @DisplayName: Terminate Pin // @DisplayName: Terminate Pin
// @Description: This sets a digital output pin to set high on flight termination // @Description: This sets a digital output pin to set high on flight termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
// @User: Advanced // @User: Advanced
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5 // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5
AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1), AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1),

Loading…
Cancel
Save