snippet_configure_drone.h
Go to the documentation of this file.
1 #ifndef SNIPPET_CONFIGURE_DRONE_H
2 #define SNIPPET_CONFIGURE_DRONE_H
3 
4 // This function will send the custom configuration to the drone
5 // It doesn't work if sent during the SDK (which runs before the configuration profiles on the drone are setup)
6 #undef ARDRONE_CONFIG_KEY_IMM_a10
7 #undef ARDRONE_CONFIG_KEY_REF_a10
8 #undef ARDRONE_CONFIG_KEY_STR_a10
9 #undef LOAD_PARAM_STR
10 #undef LOAD_PARAM_NUM
11 
12 #define SEND_PARAM_NUM(NAME,CATEGORY,DEFAULT) \
13 { \
14  if(ardrone_application_default_config.NAME!=DEFAULT) \
15  { \
16  ROS_INFO(" SEND: "#CATEGORY"/"#NAME" = %f (DEFAULT = %f)", (float)ardrone_application_default_config.NAME, (float)DEFAULT); \
17  ARDRONE_TOOL_CONFIGURATION_ADDEVENT (NAME, &ardrone_application_default_config.NAME, NULL); \
18  } \
19 }
20 
21 #define SEND_PARAM_STR(NAME,CATEGORY,DEFAULT) \
22 { \
23  if(0!=strcmp(ardrone_application_default_config.NAME,DEFAULT)) \
24  { \
25  ROS_INFO("SEND: "#CATEGORY"/"#NAME" = %s (DEFAULT = %s)", ardrone_application_default_config.NAME, DEFAULT); \
26  ARDRONE_TOOL_CONFIGURATION_ADDEVENT (NAME, ardrone_application_default_config.NAME, NULL); \
27  } \
28 }
29 
30 // firstly we send the CAT_COMMON parameters, for example outdoor, as these settings can affect where the other parameters are stored
31 #define ARDRONE_CONFIG_KEY_REF_a10(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, RW_CUSTOM, DEFAULT, CALLBACK, CATEGORY) //do nothing for reference-only parameters
32 #define ARDRONE_CONFIG_KEY_IMM_a10(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, RW_CUSTOM, DEFAULT, CALLBACK, CATEGORY) { if(0!=strcmp(KEY,"custom") && CATEGORY==CAT_COMMON && ((RW & K_WRITE) != 0 || (RW_CUSTOM & K_WRITE) != 0)) SEND_PARAM_NUM(NAME,CATEGORY,DEFAULT) } // parameters under the custom key are for control of application/user/session, we don't want to change these!
33 #define ARDRONE_CONFIG_KEY_STR_a10(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, RW_CUSTOM, DEFAULT, CALLBACK, CATEGORY) { if(0!=strcmp(KEY,"custom") && CATEGORY==CAT_COMMON && ((RW & K_WRITE) != 0 || (RW_CUSTOM & K_WRITE) != 0)) SEND_PARAM_STR(NAME,CATEGORY,DEFAULT) }
34 
35 #include <config_keys.h> // include the parameter definitions, which will be replaced by the above
36 
37 #undef ARDRONE_CONFIG_KEY_IMM_a10
38 #undef ARDRONE_CONFIG_KEY_STR_a10
39 
40 // then we send the rest of the parameters. The problem is if we send euler_angle_max (for example) before sending outdoor, it will get written to the wrong parameter
41 // (indoor_ not outdoor_euler_angle_max) and then will be overwritten by the default when changing state from indoor to outdoor, so we need to send common parameters first.
42 #define ARDRONE_CONFIG_KEY_IMM_a10(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, RW_CUSTOM, DEFAULT, CALLBACK, CATEGORY) { if(0!=strcmp(KEY,"custom") && CATEGORY!=CAT_COMMON && ((RW & K_WRITE) != 0 || (RW_CUSTOM & K_WRITE) != 0)) SEND_PARAM_NUM(NAME,CATEGORY,DEFAULT) } // parameters under the custom key are for control of application/user/session, we don't want to change these!
43 #define ARDRONE_CONFIG_KEY_STR_a10(KEY, NAME, INI_TYPE, C_TYPE, C_TYPE_PTR, RW, RW_CUSTOM, DEFAULT, CALLBACK, CATEGORY) { if(0!=strcmp(KEY,"custom") && CATEGORY!=CAT_COMMON && ((RW & K_WRITE) != 0 || (RW_CUSTOM & K_WRITE) != 0)) SEND_PARAM_STR(NAME,CATEGORY,DEFAULT) }
44 
45 #include <config_keys.h> // include the parameter definitions, which will be replaced by the above
46 
47 #undef SEND_PARAM_NUM
48 #undef SEND_PARAM_STR
49 #undef ARDRONE_CONFIG_KEY_IMM_a10
50 #undef ARDRONE_CONFIG_KEY_REF_a10
51 #undef ARDRONE_CONFIG_KEY_STR_a10
52 
53 
54 #define NAVDATA_STRUCTS_INITIALIZE
56 #undef NAVDATA_STRUCTS_INITIALIZE
57 
58 #endif // SNIPPET_CONFIGURE_DRONE_H


ardrone_autonomy
Author(s): Mani Monajjemi, Mani Monajjemi
autogenerated on Mon Jun 10 2019 12:39:49