ardrone_sdk.cpp
Go to the documentation of this file.
00001 #include <ardrone_autonomy/ardrone_sdk.h>
00002 #include <ardrone_autonomy/video.h>
00003 #include <ardrone_autonomy/teleop_twist.h>
00004 
00005 
00006 navdata_unpacked_t *shared_raw_navdata;
00007 ros::Time shared_navdata_receive_time;
00008 
00009 vp_os_mutex_t navdata_lock;
00010 vp_os_mutex_t video_lock;
00011 vp_os_mutex_t twist_lock;
00012 
00013 long int current_navdata_id = 0;
00014 
00015 ARDroneDriver* rosDriver;
00016 
00017 int32_t looprate;
00018 bool realtime_navdata;
00019 bool realtime_video;
00020 
00021 int32_t should_exit;
00022 
00023 extern "C" {
00024     vp_stages_latency_estimation_config_t vlat;
00025 
00026 
00027     DEFINE_THREAD_ROUTINE(update_ros, data)
00028     {
00029         PRINT("Thread `update_ros` started \n ");
00030         ARDroneDriver* driver = (ARDroneDriver *) data;
00031         driver->run();
00032         return (THREAD_RET) 0;
00033     }
00034     
00035          C_RESULT ardrone_tool_init_custom(void) 
00036      {
00037      should_exit = 0;
00038      vp_os_mutex_init(&navdata_lock);
00039      vp_os_mutex_init(&video_lock);
00040      vp_os_mutex_init(&twist_lock);
00041 
00042      rosDriver = new ARDroneDriver();
00043      int _w, _h;
00044         
00045         if (IS_ARDRONE2)
00046         {
00047             ardrone_application_default_config.video_codec = H264_360P_CODEC;
00048             _w = D2_STREAM_WIDTH;
00049             _h = D2_STREAM_HEIGHT;
00050         }
00051         else if (IS_ARDRONE1)
00052         {
00053             ardrone_application_default_config.video_codec = UVLC_CODEC;
00054             _w = D1_STREAM_WIDTH;
00055             _h = D1_STREAM_HEIGHT;
00056                    
00057         }
00058         else
00059         {
00060             printf("Something must be really wrong with the SDK!");
00061         }
00062 
00063         ros::param::param("~looprate",looprate,50);
00064         ros::param::param("~realtime_navdata",realtime_navdata,false);
00065         ros::param::param("~realtime_video",realtime_video,false);
00066 
00067         // SET SOME NON-STANDARD DEFAULT VALUES FOR THE DRIVER
00068         // THESE CAN BE OVERWRITTEN BY ROS PARAMETERS (below)
00069         ardrone_application_default_config.bitrate_ctrl_mode = VBC_MODE_DISABLED;
00070         if (IS_ARDRONE2)
00071         {
00072             ardrone_application_default_config.max_bitrate = 4000;
00073         }
00074 
00075         ardrone_application_default_config.navdata_options = NAVDATA_OPTION_FULL_MASK;        
00076         ardrone_application_default_config.video_channel = ZAP_CHANNEL_HORI;
00077         ardrone_application_default_config.control_level = (0 << CONTROL_LEVEL_COMBINED_YAW);
00078         ardrone_application_default_config.flying_mode = FLYING_MODE_FREE_FLIGHT;
00079 
00080 
00081         // LOAD THE CUSTOM CONFIGURATION FROM ROS PARAMETERS
00082         // all possible configuration parameters are stored in config_keys.h (and documented in the manual)
00083         // taking inspiration from ardrone_tool_configuration.c, we define some macros that replace these parameter definitions
00084         // with a function which attempts to read corresponding ros parameters, and then if successful, sets the parameter value for the drone
00085         // Note that we don't actually send these parameters to the drone, otherwise they will be overwritten when the profiles are created
00086         // in a later stage of the ARDrone initialization.
00087 
00088         #undef ARDRONE_CONFIG_KEY_IMM_a10
00089         #undef ARDRONE_CONFIG_KEY_REF_a10
00090         #undef ARDRONE_CONFIG_KEY_STR_a10
00091         #undef LOAD_PARAM_STR
00092         #undef LOAD_PARAM_NUM
00093 
00094         #define LOAD_PARAM_NUM(NAME,C_TYPE,DEFAULT)                                                                             \
00095             {                                                                                                                   \
00096               double param;                                                                                                     \
00097               ROS_DEBUG("CHECK: "#NAME" (Default = "#DEFAULT" = %f)",(float)DEFAULT);                                           \
00098               if(ros::param::get("~"#NAME,param))                                                                               \
00099               {                                                                                                                 \
00100                 ardrone_application_default_config.NAME = (C_TYPE)param;                                                        \
00101                 ROS_DEBUG("SET: "#NAME" = %f (DEFAULT = %f)", (float)ardrone_application_default_config.NAME, (float)DEFAULT);  \
00102               }                                                                                                                 \
00103             }
00104 
00105         #define LOAD_PARAM_STR(NAME,DEFAULT)                                                                                    \
00106             {                                                                                                                   \
00107               std::string param;                                                                                                \
00108               ROS_DEBUG("CHECK: "#NAME" (Default = "#DEFAULT" = %s)",DEFAULT);                                                  \
00109               if(ros::param::get("~"#NAME,param))                                                                               \
00110               {                                                                                                                 \
00111                 param = param.substr(0,STRING_T_SIZE-1);                                                                        \
00112                 strcpy(ardrone_application_default_config.NAME , param.c_str());                                                \
00113                 ROS_DEBUG("SET: "#NAME" = %s (DEFAULT = %s)", ardrone_application_default_config.NAME, DEFAULT);                \      
00114               }                                                                                                                 \
00115             }
00116 
00117         #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
00118         #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") && ((RW & K_WRITE) != 0 || (RW_CUSTOM & K_WRITE) != 0)) LOAD_PARAM_NUM(NAME,C_TYPE, DEFAULT) } // parameters under the custom key are for control of application/user/session, we don't want to change these!
00119         #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") && ((RW & K_WRITE) != 0 || (RW_CUSTOM & K_WRITE) != 0)) LOAD_PARAM_STR(NAME, DEFAULT) }
00120 
00121         #include <config_keys.h> // include the parameter definitions, which will be replaced by the above
00122 
00123         #undef LOAD_PARAM_NUM
00124         #undef LOAD_PARAM_STR
00125         #undef ARDRONE_CONFIG_KEY_IMM_a10
00126         #undef ARDRONE_CONFIG_KEY_REF_a10
00127         #undef ARDRONE_CONFIG_KEY_STR_a10
00128 
00129         // Now we delete any old configuration that we may have stored, this is so the profiles will be reinitialized to drone default before being updated with the potentially new set of custom parameters that we specify above.
00130         // We have to do this because only non-default parameters are sent, so if we delete a ros_param, the local parameter will be not be changed (above), thus will remain default and thus won't be updated on the drone - a problem if old profiles exist.
00131 
00132         char buffer[MULTICONFIG_ID_SIZE+1];
00133         
00134         sprintf(buffer,"-%s",usr_id);
00135         printf("Deleting Profile %s\n",buffer);
00136         ARDRONE_TOOL_CONFIGURATION_ADDEVENT (profile_id, buffer, NULL);
00137 
00138         sprintf(buffer,"-%s",app_id);
00139         printf("Deleting Application %s\n",buffer);
00140         ARDRONE_TOOL_CONFIGURATION_ADDEVENT (application_id, buffer, NULL);
00141 
00142         // Now continue with the rest of the initialization
00143 
00144         ardrone_tool_input_add(&teleop);
00145         uint8_t post_stages_index = 0;
00146 
00147         //Alloc structs
00148         specific_parameters_t * params             = (specific_parameters_t *)vp_os_calloc(1,sizeof(specific_parameters_t));
00149         specific_stages_t * driver_pre_stages  = (specific_stages_t*)vp_os_calloc(1, sizeof(specific_stages_t));
00150         specific_stages_t * driver_post_stages = (specific_stages_t*)vp_os_calloc(1, sizeof(specific_stages_t));
00151         vp_api_picture_t  * in_picture             = (vp_api_picture_t*) vp_os_calloc(1, sizeof(vp_api_picture_t));
00152         vp_api_picture_t  * out_picture            = (vp_api_picture_t*) vp_os_calloc(1, sizeof(vp_api_picture_t));
00153 
00154         in_picture->width          = _w;
00155         in_picture->height         = _h;
00156 
00157         out_picture->framerate     = 20;
00158         out_picture->format        = PIX_FMT_RGB24;
00159         out_picture->width         = _w;
00160         out_picture->height        = _h;
00161 
00162         out_picture->y_buf         = (uint8_t*) vp_os_malloc( _w * _h * 3 );
00163         out_picture->cr_buf        = NULL;
00164         out_picture->cb_buf        = NULL;
00165 
00166         out_picture->y_line_size   = _w * 3;
00167         out_picture->cb_line_size  = 0;
00168         out_picture->cr_line_size  = 0;
00169         
00170         //Alloc the lists
00171         driver_pre_stages->stages_list  = NULL;
00172         driver_post_stages->stages_list = (vp_api_io_stage_t*)vp_os_calloc(NB_DRIVER_POST_STAGES,sizeof(vp_api_io_stage_t));
00173         
00174         //Fill the POST-stages------------------------------------------------------
00175 //        vp_os_memset (&vlat, 0x0, sizeof (vlat));
00176 //        vlat.state = (vp_stages_latency_estimation_state) 0;
00177 //        //vlat.last_decoded_frame_info= (void *)&vec;
00178 //        driver_post_stages->stages_list[post_stages_index].name    = "LatencyEst";
00179 //        driver_post_stages->stages_list[post_stages_index].type    = VP_API_FILTER_DECODER;
00180 //        driver_post_stages->stages_list[post_stages_index].cfg     = (void *)&vlat;
00181 //        driver_post_stages->stages_list[post_stages_index++].funcs = vp_stages_latency_estimation_funcs;
00182     
00183         driver_post_stages->stages_list[post_stages_index].name    = "ExtractData";
00184         driver_post_stages->stages_list[post_stages_index].type    = VP_API_OUTPUT_SDL;
00185         driver_post_stages->stages_list[post_stages_index].cfg     = NULL;
00186         driver_post_stages->stages_list[post_stages_index++].funcs   = vp_stages_export_funcs;
00187         
00188         driver_pre_stages->length  = 0;
00189         driver_post_stages->length = post_stages_index;
00190         
00191         params->in_pic = in_picture;
00192         params->out_pic = out_picture;
00193         params->pre_processing_stages_list  = driver_pre_stages;
00194         params->post_processing_stages_list = driver_post_stages;
00195         params->needSetPriority = 1;
00196         params->priority = 31;
00197         // Using the provided threaded pipeline implementation from SDK
00198         START_THREAD(video_stage, params);
00199         video_stage_init();
00200         if (ARDRONE_VERSION() >= 2)
00201         {
00202             START_THREAD (video_recorder, NULL);
00203             video_recorder_init ();
00204             video_recorder_resume_thread();
00205         }
00206         // Threads do not start automatically
00207         video_stage_resume_thread();
00208         ardrone_tool_set_refresh_time(25);
00209         //rosDriver->configure_drone();
00210                 START_THREAD(update_ros, rosDriver);
00211                 return C_OK;
00212         }
00213     
00214     C_RESULT ardrone_tool_shutdown_custom() 
00215     {
00216         PRINT("Shutting down ... \n ");
00217         JOIN_THREAD(update_ros);
00218         delete rosDriver;
00219         video_stage_resume_thread();
00220         ardrone_tool_input_remove(&teleop);
00221         return C_OK;
00222     }
00223     
00224         C_RESULT navdata_custom_init(void *) {
00225                 return C_OK;
00226         }
00227 
00228     C_RESULT navdata_custom_process(const navdata_unpacked_t * const pnd) {
00229         vp_os_mutex_lock(&navdata_lock);
00230         shared_navdata_receive_time = ros::Time::now();
00231         shared_raw_navdata = (navdata_unpacked_t*)pnd;
00232 
00233         if(realtime_navdata)
00234         {
00235             rosDriver->PublishNavdataTypes(*shared_raw_navdata, shared_navdata_receive_time); //if we're publishing navdata at full speed, publish!
00236             rosDriver->publish_navdata(*shared_raw_navdata, shared_navdata_receive_time);
00237         }
00238 
00239         current_navdata_id++;
00240         vp_os_mutex_unlock(&navdata_lock);
00241                 return C_OK;
00242         }
00243 
00244         C_RESULT navdata_custom_release() {
00245                 return C_OK;
00246         }
00247     
00248     bool_t ardrone_tool_exit() {
00249         return (should_exit == 1);
00250     }
00251     
00252         BEGIN_THREAD_TABLE
00253     THREAD_TABLE_ENTRY(video_stage, 31)
00254     THREAD_TABLE_ENTRY(update_ros, 43)
00255     THREAD_TABLE_ENTRY(video_recorder, 20)
00256     THREAD_TABLE_ENTRY(navdata_update, 31)
00257 //      THREAD_TABLE_ENTRY(ATcodec_Commands_Client, 43)
00258         THREAD_TABLE_ENTRY(ardrone_control, 31)
00259         END_THREAD_TABLE
00260 
00261         BEGIN_NAVDATA_HANDLER_TABLE
00262         NAVDATA_HANDLER_TABLE_ENTRY(
00263                         navdata_custom_init,
00264                         navdata_custom_process,
00265                         navdata_custom_release,
00266                         NULL)
00267         END_NAVDATA_HANDLER_TABLE
00268 }
00269 


ardrone_autonomy
Author(s): Mani Monajjemi, Mani Monajjemi
autogenerated on Sun Oct 5 2014 22:17:06