mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 16:03:58 -04:00
Copter: minor user hooks cleanup
Only define and call functions if the appropriate #define in APM_Config.h has been added
This commit is contained in:
parent
6a173eb7ad
commit
5b00ce24ed
@ -24,11 +24,11 @@
|
|||||||
|
|
||||||
// User Hooks : For User Developed code that you wish to run
|
// User Hooks : For User Developed code that you wish to run
|
||||||
// Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below).
|
// Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below).
|
||||||
#define USERHOOK_VARIABLES "UserVariables.h"
|
//#define USERHOOK_VARIABLES "UserVariables.h"
|
||||||
// Put your custom code into the UserCode.pde with function names matching those listed below and ensure the appropriate #define below is uncommented below
|
// Put your custom code into the UserCode.pde with function names matching those listed below and ensure the appropriate #define below is uncommented below
|
||||||
#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
|
//#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
|
||||||
//#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
|
//#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
|
||||||
#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
|
//#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
|
||||||
//#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
|
||||||
|
@ -1,13 +1,44 @@
|
|||||||
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
|
#ifdef USERHOOK_INIT
|
||||||
void userhook_init()
|
void userhook_init()
|
||||||
{
|
{
|
||||||
// put your initialisation code here
|
// put your initialisation code here
|
||||||
|
// this will be called once at start-up
|
||||||
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USERHOOK_FASTLOOP
|
||||||
|
void userhook_FastLoop()
|
||||||
|
{
|
||||||
|
// put your 100Hz code here
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USERHOOK_50HZLOOP
|
||||||
void userhook_50Hz()
|
void userhook_50Hz()
|
||||||
{
|
{
|
||||||
// put your 50Hz code here
|
// put your 50Hz code here
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USERHOOK_MEDIUMLOOP
|
||||||
|
void userhook_MediumLoop()
|
||||||
|
{
|
||||||
|
// put your 10Hz code here
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USERHOOK_SLOWLOOP
|
||||||
|
void userhook_SlowLoop()
|
||||||
|
{
|
||||||
|
// put your 3.3Hz code here
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USERHOOK_SUPERSLOWLOOP
|
||||||
|
void userhook_SuperSlowLoop()
|
||||||
|
{
|
||||||
|
// put your 1Hz code here
|
||||||
|
}
|
||||||
|
#endif
|
@ -1,13 +1,19 @@
|
|||||||
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
// user defined variables
|
// user defined variables
|
||||||
|
|
||||||
// example variables used in Wii camera testing - replace with your own
|
// example variables used in Wii camera testing - replace with your own
|
||||||
// variables
|
// variables
|
||||||
|
#ifdef USERHOOK_VARIABLES
|
||||||
|
|
||||||
#if WII_CAMERA == 1
|
#if WII_CAMERA == 1
|
||||||
WiiCamera ircam;
|
WiiCamera ircam;
|
||||||
int WiiRange=0;
|
int WiiRange=0;
|
||||||
int WiiRotation=0;
|
int WiiRotation=0;
|
||||||
int WiiDisplacementX=0;
|
int WiiDisplacementX=0;
|
||||||
int WiiDisplacementY=0;
|
int WiiDisplacementY=0;
|
||||||
#endif
|
#endif // WII_CAMERA
|
||||||
|
|
||||||
|
#endif // USERHOOK_VARIABLES
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user