mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: Report what channel is used for rudder arming
This commit is contained in:
parent
132fe82ad2
commit
5104e4bd13
@ -68,6 +68,11 @@ bool RC_Channels_Rover::has_valid_input() const
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
RC_Channel * RC_Channels_Rover::get_arming_channel(void) const
|
||||||
|
{
|
||||||
|
return rover.channel_steer;
|
||||||
|
}
|
||||||
|
|
||||||
void RC_Channel_Rover::do_aux_function_change_mode(Mode &mode,
|
void RC_Channel_Rover::do_aux_function_change_mode(Mode &mode,
|
||||||
const aux_switch_pos_t ch_flag)
|
const aux_switch_pos_t ch_flag)
|
||||||
{
|
{
|
||||||
|
@ -34,6 +34,8 @@ public:
|
|||||||
|
|
||||||
bool has_valid_input() const override;
|
bool has_valid_input() const override;
|
||||||
|
|
||||||
|
RC_Channel *get_arming_channel(void) const override;
|
||||||
|
|
||||||
RC_Channel_Rover obj_channels[NUM_RC_CHANNELS];
|
RC_Channel_Rover obj_channels[NUM_RC_CHANNELS];
|
||||||
|
|
||||||
RC_Channel_Rover *channel(const uint8_t chan) override {
|
RC_Channel_Rover *channel(const uint8_t chan) override {
|
||||||
|
Loading…
Reference in New Issue
Block a user