Browse Source

Copter: fix userhook aux switches

Functions userhook_auxSwitch1, userhook_auxSwitch2, and userhook_auxSwitch3 had the wrong argument type resulting in a compilation error.
gps-1.3.1
Miloš Petrašinović 3 years ago committed by Randy Mackay
parent
commit
063e24c723
  1. 6
      ArduCopter/Copter.h
  2. 6
      ArduCopter/UserCode.cpp

6
ArduCopter/Copter.h

@ -901,9 +901,9 @@ private: @@ -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;

6
ArduCopter/UserCode.cpp

@ -44,17 +44,17 @@ void Copter::userhook_SuperSlowLoop() @@ -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…
Cancel
Save