mirror of https://github.com/ArduPilot/ardupilot
44 lines
952 B
C++
44 lines
952 B
C++
#pragma once
|
|
|
|
#include <RC_Channel/RC_Channel.h>
|
|
#include "Rover.h"
|
|
#include "mode.h"
|
|
|
|
class RC_Channel_Rover : public RC_Channel
|
|
{
|
|
|
|
public:
|
|
|
|
protected:
|
|
|
|
void init_aux_function(aux_func_t ch_option, aux_switch_pos_t) override;
|
|
void do_aux_function(aux_func_t ch_option, aux_switch_pos_t) override;
|
|
|
|
// called when the mode switch changes position:
|
|
void mode_switch_changed(modeswitch_pos_t new_pos) override;
|
|
|
|
private:
|
|
|
|
void do_aux_function_change_mode(Mode &mode,
|
|
const aux_switch_pos_t ch_flag);
|
|
|
|
};
|
|
|
|
class RC_Channels_Rover : public RC_Channels
|
|
{
|
|
bool has_valid_input() const override;
|
|
|
|
int8_t flight_mode_channel_number() const override;
|
|
|
|
public:
|
|
|
|
RC_Channel_Rover obj_channels[NUM_RC_CHANNELS];
|
|
RC_Channel_Rover *channel(const uint8_t chan) override {
|
|
if (chan > NUM_RC_CHANNELS) {
|
|
return nullptr;
|
|
}
|
|
return &obj_channels[chan];
|
|
}
|
|
|
|
};
|