mirror of https://github.com/ArduPilot/ardupilot
Copter: fix userhook aux switches
Functions userhook_auxSwitch1, userhook_auxSwitch2, and userhook_auxSwitch3 had the wrong argument type resulting in a compilation error.
This commit is contained in:
parent
a04bbad45e
commit
063e24c723
|
@ -901,9 +901,9 @@ private:
|
|||
void userhook_MediumLoop();
|
||||
void userhook_SlowLoop();
|
||||
void userhook_SuperSlowLoop();
|
||||
void userhook_auxSwitch1(uint8_t ch_flag);
|
||||
void userhook_auxSwitch2(uint8_t ch_flag);
|
||||
void userhook_auxSwitch3(uint8_t ch_flag);
|
||||
void userhook_auxSwitch1(const RC_Channel::AuxSwitchPos ch_flag);
|
||||
void userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag);
|
||||
void userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag);
|
||||
|
||||
// vehicle specific waypoint info helpers
|
||||
bool get_wp_distance_m(float &distance) const override;
|
||||
|
|
|
@ -44,17 +44,17 @@ void Copter::userhook_SuperSlowLoop()
|
|||
#endif
|
||||
|
||||
#ifdef USERHOOK_AUXSWITCH
|
||||
void Copter::userhook_auxSwitch1(uint8_t ch_flag)
|
||||
void Copter::userhook_auxSwitch1(const RC_Channel::AuxSwitchPos ch_flag)
|
||||
{
|
||||
// put your aux switch #1 handler here (CHx_OPT = 47)
|
||||
}
|
||||
|
||||
void Copter::userhook_auxSwitch2(uint8_t ch_flag)
|
||||
void Copter::userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag)
|
||||
{
|
||||
// put your aux switch #2 handler here (CHx_OPT = 48)
|
||||
}
|
||||
|
||||
void Copter::userhook_auxSwitch3(uint8_t ch_flag)
|
||||
void Copter::userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag)
|
||||
{
|
||||
// put your aux switch #3 handler here (CHx_OPT = 49)
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue