mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: implement user auxswitch functions
This commit is contained in:
parent
1377943eb3
commit
ea3de59107
@ -65,3 +65,4 @@
|
|||||||
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
|
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
|
||||||
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
|
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
|
||||||
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
|
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz
|
||||||
|
//#define USERHOOK_AUXSWITCH ENABLED // for code to handle user aux switches
|
||||||
|
@ -937,6 +937,9 @@ private:
|
|||||||
void userhook_MediumLoop();
|
void userhook_MediumLoop();
|
||||||
void userhook_SlowLoop();
|
void userhook_SlowLoop();
|
||||||
void userhook_SuperSlowLoop();
|
void userhook_SuperSlowLoop();
|
||||||
|
void userhook_auxSwitch1(uint8_t ch_flag);
|
||||||
|
void userhook_auxSwitch2(uint8_t ch_flag);
|
||||||
|
void userhook_auxSwitch3(uint8_t ch_flag);
|
||||||
|
|
||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
|
|
||||||
|
@ -42,3 +42,20 @@ void Copter::userhook_SuperSlowLoop()
|
|||||||
// put your 1Hz code here
|
// put your 1Hz code here
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USERHOOK_AUXSWITCH
|
||||||
|
void Copter::userhook_auxSwitch1(uint8_t ch_flag)
|
||||||
|
{
|
||||||
|
// put your aux switch #1 handler here (CHx_OPT = 47)
|
||||||
|
}
|
||||||
|
|
||||||
|
void Copter::userhook_auxSwitch2(uint8_t ch_flag)
|
||||||
|
{
|
||||||
|
// put your aux switch #2 handler here (CHx_OPT = 48)
|
||||||
|
}
|
||||||
|
|
||||||
|
void Copter::userhook_auxSwitch3(uint8_t ch_flag)
|
||||||
|
{
|
||||||
|
// put your aux switch #3 handler here (CHx_OPT = 49)
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
@ -75,6 +75,9 @@ enum aux_sw_func {
|
|||||||
AUXSW_WINCH_ENABLE = 44, // winch enable/disable
|
AUXSW_WINCH_ENABLE = 44, // winch enable/disable
|
||||||
AUXSW_WINCH_CONTROL = 45, // winch control
|
AUXSW_WINCH_CONTROL = 45, // winch control
|
||||||
AUXSW_RC_OVERRIDE_ENABLE = 46, // enable RC Override
|
AUXSW_RC_OVERRIDE_ENABLE = 46, // enable RC Override
|
||||||
|
AUXSW_USER_FUNC1 = 47, // user function #1
|
||||||
|
AUXSW_USER_FUNC2 = 48, // user function #2
|
||||||
|
AUXSW_USER_FUNC3 = 49, // user function #3
|
||||||
AUXSW_SWITCH_MAX,
|
AUXSW_SWITCH_MAX,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -727,6 +727,20 @@ void Copter::do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#ifdef USERHOOK_AUXSWITCH
|
||||||
|
case AUXSW_USER_FUNC1:
|
||||||
|
userhook_auxSwitch1(ch_flag);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case AUXSW_USER_FUNC2:
|
||||||
|
userhook_auxSwitch2(ch_flag);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case AUXSW_USER_FUNC3:
|
||||||
|
userhook_auxSwitch3(ch_flag);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user