ardrone_driver.cpp
Go to the documentation of this file.
00001 
00025 #include <signal.h>
00026 #include <string>
00027 #include <algorithm>
00028 #include <vector>
00029 
00030 #include <ardrone_autonomy/ardrone_driver.h>
00031 #include <ardrone_autonomy/teleop_twist.h>
00032 #include <ardrone_autonomy/video.h>
00033 
00034 
00036 // class ARDroneDriver
00038 
00039 ARDroneDriver::ARDroneDriver()
00040   : private_nh("~"),
00041     image_transport(node_handle),
00042     // Ugly: This has been defined in the template file. Cleaner way to guarantee initilaztion?
00043     initialized_navdata_publishers(false),
00044     last_frame_id(-1),
00045     last_navdata_id(-1),
00046     is_inited(false),
00047     last_receive_time(0.0)
00048 {
00049   cmd_vel_sub = node_handle.subscribe("cmd_vel", 1, &CmdVelCallback);
00050   takeoff_sub = node_handle.subscribe("ardrone/takeoff", 1, &TakeoffCallback);
00051   reset_sub = node_handle.subscribe("ardrone/reset", 1, &ResetCallback);
00052   land_sub = node_handle.subscribe("ardrone/land", 1, &LandCallback);
00053   image_pub = image_transport.advertiseCamera("ardrone/image_raw", 10);
00054   hori_pub = image_transport.advertiseCamera("ardrone/front/image_raw", 10);
00055   vert_pub = image_transport.advertiseCamera("ardrone/bottom/image_raw", 10);
00056   toggle_cam_srv = node_handle.advertiseService("ardrone/togglecam", ToggleCamCallback);
00057   set_cam_channel_srv = node_handle.advertiseService("ardrone/setcamchannel", SetCamChannelCallback);
00058   set_led_animation_srv = node_handle.advertiseService("ardrone/setledanimation", SetLedAnimationCallback);
00059   flat_trim_srv = node_handle.advertiseService("ardrone/flattrim", FlatTrimCallback);
00060   set_flight_anim_srv = node_handle.advertiseService("ardrone/setflightanimation", SetFlightAnimationCallback);
00061   set_record_srv = node_handle.advertiseService("ardrone/setrecord", SetRecordCallback);
00062 
00063   /* TF Frames */
00064   std::string tf_prefix_key;
00065   private_nh.searchParam("tf_prefix", tf_prefix_key);
00066   private_nh.param(tf_prefix_key, tf_prefix, std::string(""));
00067   private_nh.param<std::string>("drone_frame_id", drone_frame_id, "ardrone_base");
00068   drone_frame_base = tf::resolve(tf_prefix, drone_frame_id + "_link");
00069   drone_frame_imu = tf::resolve(tf_prefix, drone_frame_id + "_imu");
00070   drone_frame_front_cam = tf::resolve(tf_prefix, drone_frame_id + "_frontcam");
00071   drone_frame_bottom_cam = tf::resolve(tf_prefix, drone_frame_id + "_bottomcam");
00072   tf_odom.frame_id_ = tf::resolve(tf_prefix, "odom");
00073 
00074   if (private_nh.hasParam("root_frame"))
00075   {
00076     ROS_WARN("Changing `root_frame` has been deprecated since version 1.4. ");
00077   }
00078 
00079   // Fill constant parts of IMU Message
00080   // If no rosparam is set then the default value of 0.0 will be assigned to all covariance values
00081   for (int i = 0; i < 9; i++)
00082   {
00083     imu_msg.linear_acceleration_covariance[i] = 0.0;
00084     imu_msg.angular_velocity_covariance[i] = 0.0;
00085     imu_msg.orientation_covariance[i] = 0.0;
00086   }
00087   ReadCovParams("~cov/imu_la", imu_msg.linear_acceleration_covariance);
00088   ReadCovParams("~cov/imu_av", imu_msg.angular_velocity_covariance);
00089   ReadCovParams("~cov/imu_or", imu_msg.orientation_covariance);
00090 
00091   if (private_nh.hasParam("do_imu_caliberation"))
00092   {
00093     ROS_WARN("IMU Caliberation has been deprecated since 1.4.");
00094   }
00095 
00096   // Camera Info Manager
00097   cinfo_hori = new camera_info_manager::CameraInfoManager(ros::NodeHandle("ardrone/front"), "ardrone_front");
00098   cinfo_vert = new camera_info_manager::CameraInfoManager(ros::NodeHandle("ardrone/bottom"), "ardrone_bottom");
00099 
00100   // TF Stuff
00101 
00102 
00103   // Front Cam to Base
00104   // TODO(mani-monaj): Precise values for Drone1 & Drone2
00105   tf_base_front = tf::StampedTransform(
00106                     tf::Transform(
00107                       tf::createQuaternionFromRPY(-90.0 * _DEG2RAD, 0.0, -90.0 * _DEG2RAD),
00108                       tf::Vector3(0.21, 0.0, 0.0)),
00109                     ros::Time::now(), drone_frame_base, drone_frame_front_cam);
00110 
00111   // Bottom Cam to Base (Bad Assumption: No translation from IMU and Base)
00112   // TODO(mani-monaj): This should be different from Drone 1 & 2.
00113   tf_base_bottom = tf::StampedTransform(
00114                      tf::Transform(
00115                        tf::createQuaternionFromRPY(180.0 * _DEG2RAD, 0.0, 90.0 * _DEG2RAD),
00116                        tf::Vector3(0.0, -0.02, 0.0)),
00117                      ros::Time::now(), drone_frame_base, drone_frame_bottom_cam);
00118 
00119   // reset odometry
00120   odometry[0] = odometry[1] = 0;
00121 }
00122 
00123 ARDroneDriver::~ARDroneDriver()
00124 {
00125   delete cinfo_hori;
00126   delete cinfo_vert;
00127 }
00128 
00129 void ARDroneDriver::run()
00130 {
00131   ros::Rate loop_rate(looprate);
00132   const ros::Time startTime = ros::Time::now();
00133   static int freq_dev = 0;
00134   while (node_handle.ok())
00135   {
00136     if (!is_inited)  // Give the Drone 5s of free time to finish init phase
00137     {
00138       if (((ros::Time::now() - startTime).toSec()) > 5.0)
00139       {
00140         is_inited = true;
00141 
00142         // Send the configuration to the drone
00143         ConfigureDrone();
00144 
00145         vp_os_mutex_lock(&navdata_lock);
00146         ROS_INFO("Successfully connected to '%s' (AR-Drone %d.0 - Firmware: %s) - Battery(%%): %d",
00147                  ardrone_control_config.ardrone_name,
00148                  (IS_ARDRONE1) ? 1 : 2,
00149                  ardrone_control_config.num_version_soft,
00150                  shared_raw_navdata_ptr->navdata_demo.vbat_flying_percentage);
00151         ROS_INFO("Navdata Publish Settings:");
00152         ROS_INFO("    Legacy Navdata Mode: %s", enabled_legacy_navdata ? "On" : "Off");
00153         ROS_INFO("    ROS Loop Rate: %d Hz", looprate);
00154         ROS_INFO("    Realtime Navdata Publish: %s", realtime_navdata ? "On" : "Off");
00155         ROS_INFO("    Realtime Video Publish: %s", realtime_video ? "On" : "Off");
00156         ROS_INFO("    Drone Navdata Send Speed: %s",
00157                  ardrone_application_default_config.navdata_demo == 0 ?
00158                    "200Hz (navdata_demo=0)" : "15Hz (navdata_demo=1)");
00159         // TODO(mani-monaj): Enabled Navdata Demo
00160         vp_os_mutex_unlock(&navdata_lock);
00161         if (ardrone_control_config.num_version_soft[0] == '0')
00162         {
00163           ROS_WARN("The AR-Drone has a suspicious Firmware number. It usually means the network link is unreliable.");
00164         }
00165         ROS_DEBUG_STREAM("Using " << tf_prefix << " to prefix TF frames.");
00166       }
00167     }
00168     else
00169     {
00170       if (!realtime_video)
00171       {
00172         vp_os_mutex_lock(&video_lock);
00173         copy_current_frame_id = current_frame_id;
00174         vp_os_mutex_unlock(&video_lock);
00175         if (copy_current_frame_id != last_frame_id)
00176         {
00177           last_frame_id = copy_current_frame_id;
00178           PublishVideo();
00179         }
00180       }
00181 
00182       if (!realtime_navdata)
00183       {
00184         vp_os_mutex_lock(&navdata_lock);
00185         copy_current_navdata_id = current_navdata_id;
00186         vp_os_mutex_unlock(&navdata_lock);
00187         if (copy_current_navdata_id != last_navdata_id)
00188         {
00189           vp_os_mutex_lock(&navdata_lock);
00190           last_navdata_id = copy_current_navdata_id;
00191 
00192           // Thread safe copy of interesting Navdata data
00193           // TODO(mani-monaj): This is a very expensive task, can we optimize here?
00194           // maybe ignoring the copy when it is not needed.
00195           const navdata_unpacked_t navdata_raw = *shared_raw_navdata_ptr;
00196           const ros::Time navdata_receive_time = shared_navdata_receive_time;
00197           vp_os_mutex_unlock(&navdata_lock);
00198 
00199           // This function is defined in the template NavdataMessageDefinitions.h template file
00200           PublishNavdataTypes(navdata_raw, navdata_receive_time);
00201           PublishNavdata(navdata_raw, navdata_receive_time);
00202           PublishOdometry(navdata_raw, navdata_receive_time);
00203         }
00204       }
00205       if (freq_dev == 0) PublishTF();
00206 
00207       // (looprate / 5)Hz  TF publish
00208       // TODO(mani-monaj): Make TF publish rate fixed
00209       freq_dev = (freq_dev + 1) % 5;
00210     }
00211     ros::spinOnce();
00212     loop_rate.sleep();
00213   }
00214   printf("ROS loop terminated ... \n");
00215 }
00216 
00217 void ARDroneDriver::ConfigureDrone()
00218 {
00219   #include "ardrone_autonomy/snippet_configure_drone.h"
00220 }
00221 
00222 double ARDroneDriver::CalcAverage(const std::vector<double> &vec)
00223 {
00224   double ret = 0.0;
00225   for (unsigned int i = 0; i < vec.size(); i++)
00226   {
00227     ret += vec[i];
00228   }
00229   return (ret / vec.size());
00230 }
00231 
00232 bool ARDroneDriver::ReadCovParams(const std::string &param_name, boost::array<double, 9> &cov_array)
00233 {
00234   XmlRpc::XmlRpcValue cov_list;
00235   std::stringstream str_stream;
00236   if (ros::param::get(param_name, cov_list))
00237   {
00238     if (cov_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00239     {
00240       ROS_WARN("Covariance values for %s is not a list", param_name.c_str());
00241       return false;
00242     }
00243 
00244     if (cov_list.size() != 9)
00245     {
00246       ROS_WARN("Covariance list size for %s is not of size 9 (Size: %d)", param_name.c_str(), cov_list.size());
00247       return false;
00248     }
00249     str_stream << param_name << " set to [";
00250     for (int32_t i = 0; i < cov_list.size(); i++)
00251     {
00252       ROS_ASSERT(cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00253       cov_array[i] = static_cast<double>(cov_list[i]);
00254       str_stream << cov_array[i] << ((i < 8) ? ", " : "");
00255     }
00256     str_stream << "]";
00257     ROS_INFO("%s", str_stream.str().c_str());
00258     return true;
00259   }
00260   else
00261   {
00262     ROS_INFO("No values found for `%s` in parameters, set all to zero.", param_name.c_str());
00263     return false;
00264   }
00265 }
00266 
00267 void ARDroneDriver::PublishVideo()
00268 {
00269   if (
00270     (image_pub.getNumSubscribers() == 0) &&
00271     (hori_pub.getNumSubscribers() == 0) &&
00272     (vert_pub.getNumSubscribers() == 0)
00273   ) return;
00274 
00275   // Camera Info (NO PIP)
00276 
00277   sensor_msgs::CameraInfo cinfo_msg_hori = cinfo_hori->getCameraInfo();
00278   sensor_msgs::CameraInfo cinfo_msg_vert = cinfo_vert->getCameraInfo();
00279 
00280   cinfo_msg_hori.header.frame_id = drone_frame_front_cam;
00281   cinfo_msg_vert.header.frame_id = drone_frame_bottom_cam;
00282 
00283   if (IS_ARDRONE1)
00284   {
00285     /*
00286     * Information on buffer and image sizes.
00287     * Buffer is always in QVGA size, however for different Camera Modes
00288     * The picture and PIP sizes are different.
00289     *
00290     * image_raw and buffer are always 320x240. In order to preserve backward compatibilty image_raw remains
00291     * always as before. Two new set of topics are added for two new cameras : /ardrone/front/xxx and /ardrone/bottom/xxx
00292     *
00293     * In Camera State 0 front image relays the buffer  and image_raw and bottom image are not updated.
00294     *
00295     * In Camera State 1 bottom image is a 174x144 crop of the buffer. The front image is not updated
00296     *
00297     * In Camera State 2 bottom image is a PIP cut of size (87x72) from buffer.
00298     * The bottom image is a (320-87)x(240) cut of the buffer.
00299     *
00300     * In Camera State 3 front image is a PIP cut of size (58x42) from buffer.
00301     * The bottom image is a (174-58)x144 crop of the buffer.
00302     */
00303     sensor_msgs::Image image_msg;
00304     sensor_msgs::Image::_data_type::iterator _it;
00305 
00306     if ((cam_state == ZAP_CHANNEL_HORI) || (cam_state == ZAP_CHANNEL_LARGE_HORI_SMALL_VERT))
00307     {
00308       image_msg.header.frame_id = drone_frame_front_cam;
00309     }
00310     else if ((cam_state == ZAP_CHANNEL_VERT) || (cam_state == ZAP_CHANNEL_LARGE_VERT_SMALL_HORI))
00311     {
00312       image_msg.header.frame_id = drone_frame_bottom_cam;
00313     }
00314     else
00315     {
00316       ROS_WARN_ONCE("Something is wrong with camera channel config.");
00317     }
00318 
00319     image_msg.width = D1_STREAM_WIDTH;
00320     image_msg.height = D1_STREAM_HEIGHT;
00321     image_msg.encoding = "rgb8";
00322     image_msg.is_bigendian = false;
00323     image_msg.step = D1_STREAM_WIDTH * 3;
00324     image_msg.data.resize(D1_STREAM_WIDTH * D1_STREAM_HEIGHT * 3);
00325 
00326     if (!realtime_video) vp_os_mutex_lock(&video_lock);
00327     image_msg.header.stamp = shared_video_receive_time;
00328     std::copy(buffer, buffer + (D1_STREAM_WIDTH * D1_STREAM_HEIGHT * 3), image_msg.data.begin());
00329     if (!realtime_video) vp_os_mutex_unlock(&video_lock);
00330 
00331     cinfo_msg_hori.header.stamp = image_msg.header.stamp;
00332     cinfo_msg_vert.header.stamp = image_msg.header.stamp;
00333 
00334     if (cam_state == ZAP_CHANNEL_HORI)
00335     {
00336       /*
00337       * Horizontal camera is activated, only /ardrone/front/ is being updated
00338       */
00339       cinfo_msg_hori.width = D1_STREAM_WIDTH;
00340       cinfo_msg_hori.height = D1_STREAM_HEIGHT;
00341 
00342       image_pub.publish(image_msg, cinfo_msg_hori);
00343       hori_pub.publish(image_msg, cinfo_msg_hori);
00344     }
00345     else if (cam_state == ZAP_CHANNEL_VERT)
00346     {
00347       /*
00348       * Vertical camera is activated, only /ardrone/bottom/ is being updated
00349       */
00350       image_msg.width = D1_VERTSTREAM_WIDTH;
00351       image_msg.height = D1_VERTSTREAM_HEIGHT;
00352       image_msg.encoding = "rgb8";
00353       image_msg.is_bigendian = false;
00354       image_msg.step = D1_VERTSTREAM_WIDTH * 3;
00355       image_msg.data.clear();
00356       image_msg.data.resize(D1_VERTSTREAM_WIDTH * D1_VERTSTREAM_HEIGHT * 3);
00357       _it = image_msg.data.begin();
00358       if (!realtime_video) vp_os_mutex_lock(&video_lock);
00359       for (int row = 0; row < D1_VERTSTREAM_HEIGHT ; row++)
00360       {
00361         int _b = row * D1_STREAM_WIDTH * 3;
00362         int _e = _b + image_msg.step;
00363         _it = std::copy(buffer + _b, buffer + _e, _it);
00364       }
00365       if (!realtime_video) vp_os_mutex_unlock(&video_lock);
00366 
00367       cinfo_msg_vert.width = D1_VERTSTREAM_WIDTH;
00368       cinfo_msg_vert.height = D1_VERTSTREAM_HEIGHT;
00369       image_pub.publish(image_msg, cinfo_msg_vert);
00370       vert_pub.publish(image_msg, cinfo_msg_vert);
00371     }
00372     else if (cam_state == ZAP_CHANNEL_LARGE_HORI_SMALL_VERT)
00373     {
00374       /*
00375       * The Picture in Picture is activated with vertical camera inside the horizontal
00376       * camera. Both /ardrone/front and /ardrone/bottom is being updated
00377       */
00378 
00379       // Front (Cropping the first 88 columns)
00380       image_msg.width = D1_STREAM_WIDTH  - D1_MODE2_PIP_WIDTH;
00381       image_msg.height = D1_STREAM_HEIGHT;
00382       image_msg.encoding = "rgb8";
00383       image_msg.is_bigendian = false;
00384       image_msg.step = (D1_STREAM_WIDTH - D1_MODE2_PIP_WIDTH) * 3;
00385       image_msg.data.clear();
00386       image_msg.data.resize((D1_STREAM_WIDTH - D1_MODE2_PIP_WIDTH)*D1_STREAM_HEIGHT * 3);
00387       _it = image_msg.data.begin();
00388       if (!realtime_video) vp_os_mutex_lock(&video_lock);
00389       for (int row = 0; row < D1_STREAM_HEIGHT; row++)
00390       {
00391         int _b = (row * D1_STREAM_WIDTH * 3) + (D1_MODE2_PIP_WIDTH * 3);
00392         int _e = _b + image_msg.step;
00393         _it = std::copy(buffer + _b, buffer + _e, _it);
00394       }
00395       if (!realtime_video) vp_os_mutex_unlock(&video_lock);
00396 
00397       cinfo_msg_hori.width = D1_STREAM_WIDTH - D1_MODE2_PIP_WIDTH;
00398       cinfo_msg_hori.height = D1_STREAM_HEIGHT;
00399       hori_pub.publish(image_msg, cinfo_msg_hori);
00400 
00401       // Bottom
00402       image_msg.width = D1_MODE2_PIP_WIDTH;
00403       image_msg.height = D1_MODE2_PIP_HEIGHT;
00404       image_msg.encoding = "rgb8";
00405       image_msg.is_bigendian = false;
00406       image_msg.step = D1_MODE2_PIP_WIDTH * 3;
00407       image_msg.data.clear();
00408       image_msg.data.resize(D1_MODE2_PIP_WIDTH * D1_MODE2_PIP_HEIGHT * 3);
00409       _it = image_msg.data.begin();
00410       if (!realtime_video) vp_os_mutex_lock(&video_lock);
00411       for (int row = 0; row < D1_MODE2_PIP_HEIGHT; row++)
00412       {
00413         int _b = row * D1_STREAM_WIDTH * 3;
00414         int _e = _b + image_msg.step;
00415         _it = std::copy(buffer + _b, buffer + _e, _it);
00416       }
00417       if (!realtime_video) vp_os_mutex_unlock(&video_lock);
00418 
00419       cinfo_msg_vert.width = D1_MODE2_PIP_WIDTH;
00420       cinfo_msg_vert.height = D1_MODE2_PIP_HEIGHT;
00421       vert_pub.publish(image_msg, cinfo_msg_vert);
00422     }
00423     else if (cam_state == ZAP_CHANNEL_LARGE_VERT_SMALL_HORI)
00424     {
00425       /*
00426       * The Picture in Picture is activated with horizontal camera inside the vertical
00427       * camera. Both /ardrone/front and /ardrone/bottom is being updated
00428       */
00429 
00430       // Bottom  (Cropping the first 58 columns)
00431       image_msg.width = D1_VERTSTREAM_WIDTH   - D1_MODE3_PIP_WIDTH;
00432       image_msg.height = D1_VERTSTREAM_HEIGHT;
00433       image_msg.encoding = "rgb8";
00434       image_msg.is_bigendian = false;
00435       image_msg.step = (D1_VERTSTREAM_WIDTH - D1_MODE3_PIP_WIDTH) * 3;
00436       image_msg.data.clear();
00437       image_msg.data.resize((D1_VERTSTREAM_WIDTH - D1_MODE3_PIP_WIDTH)* D1_VERTSTREAM_HEIGHT * 3);
00438       _it = image_msg.data.begin();
00439       for (int row = 0; row < D1_VERTSTREAM_HEIGHT; row++)
00440       {
00441         int _b = (row * (D1_STREAM_WIDTH * 3)) + (D1_MODE3_PIP_WIDTH * 3);
00442         int _e = _b + image_msg.step;
00443         if (!realtime_video) vp_os_mutex_lock(&video_lock);
00444         _it = std::copy(buffer + _b, buffer + _e, _it);
00445         if (!realtime_video) vp_os_mutex_unlock(&video_lock);
00446       }
00447 
00448       cinfo_msg_vert.width = D1_VERTSTREAM_WIDTH - D1_MODE3_PIP_WIDTH;
00449       cinfo_msg_vert.height = D1_VERTSTREAM_HEIGHT;
00450       vert_pub.publish(image_msg, cinfo_msg_vert);
00451 
00452       // Front
00453       image_msg.width = D1_MODE3_PIP_WIDTH;
00454       image_msg.height = D1_MODE3_PIP_HEIGHT;
00455       image_msg.encoding = "rgb8";
00456       image_msg.is_bigendian = false;
00457       image_msg.step = D1_MODE3_PIP_WIDTH * 3;
00458       image_msg.data.clear();
00459       image_msg.data.resize(D1_MODE3_PIP_WIDTH * D1_MODE3_PIP_HEIGHT * 3);
00460       _it = image_msg.data.begin();
00461       if (!realtime_video) vp_os_mutex_lock(&video_lock);
00462       for (int row = 0; row < D1_MODE3_PIP_HEIGHT; row++)
00463       {
00464         int _b = row * D1_STREAM_WIDTH * 3;
00465         int _e = _b + image_msg.step;
00466         _it = std::copy(buffer + _b, buffer + _e, _it);
00467       }
00468       if (!realtime_video) vp_os_mutex_unlock(&video_lock);
00469 
00470       cinfo_msg_hori.width = D1_MODE3_PIP_WIDTH;
00471       cinfo_msg_hori.height = D1_MODE3_PIP_HEIGHT;
00472       hori_pub.publish(image_msg, cinfo_msg_hori);
00473     }
00474   }
00475 
00481   if (IS_ARDRONE2)
00482   {
00483     sensor_msgs::Image image_msg;
00484     sensor_msgs::Image::_data_type::iterator _it;
00485 
00486     if (cam_state == ZAP_CHANNEL_HORI)
00487     {
00488       image_msg.header.frame_id = drone_frame_front_cam;
00489     }
00490     else if (cam_state == ZAP_CHANNEL_VERT)
00491     {
00492       image_msg.header.frame_id = drone_frame_bottom_cam;
00493     }
00494     else
00495     {
00496       ROS_WARN_ONCE("Something is wrong with camera channel config.");
00497     }
00498 
00499     image_msg.width = D2_STREAM_WIDTH;
00500     image_msg.height = D2_STREAM_HEIGHT;
00501     image_msg.encoding = "rgb8";
00502     image_msg.is_bigendian = false;
00503     image_msg.step = D2_STREAM_WIDTH * 3;
00504     image_msg.data.resize(D2_STREAM_WIDTH * D2_STREAM_HEIGHT * 3);
00505     if (!realtime_video) vp_os_mutex_lock(&video_lock);
00506     image_msg.header.stamp = shared_video_receive_time;
00507     std::copy(buffer, buffer + (D2_STREAM_WIDTH * D2_STREAM_HEIGHT * 3), image_msg.data.begin());
00508     if (!realtime_video) vp_os_mutex_unlock(&video_lock);
00509     // We only put the width and height in here.
00510 
00511     cinfo_msg_hori.header.stamp = image_msg.header.stamp;
00512     cinfo_msg_vert.header.stamp = image_msg.header.stamp;
00513 
00514     if (cam_state == ZAP_CHANNEL_HORI)
00515     {
00516       /*
00517       * Horizontal camera is activated, only /ardrone/front/ is being updated
00518       */
00519       cinfo_msg_hori.width = D2_STREAM_WIDTH;
00520       cinfo_msg_hori.height = D2_STREAM_HEIGHT;
00521       image_pub.publish(image_msg, cinfo_msg_hori);  // /ardrone
00522       hori_pub.publish(image_msg, cinfo_msg_hori);
00523     }
00524     else if (cam_state == ZAP_CHANNEL_VERT)
00525     {
00526       /*
00527       * Vertical camera is activated, only /ardrone/bottom/ is being updated
00528       */
00529       cinfo_msg_vert.width = D2_STREAM_WIDTH;
00530       cinfo_msg_vert.height = D2_STREAM_HEIGHT;
00531       image_pub.publish(image_msg, cinfo_msg_vert);  // /ardrone
00532       vert_pub.publish(image_msg, cinfo_msg_vert);
00533     }
00534   }
00535 }
00536 
00537 void ARDroneDriver::PublishNavdata(const navdata_unpacked_t &navdata_raw, const ros::Time &navdata_receive_time)
00538 {
00539   if (!enabled_legacy_navdata ||
00540       ((navdata_pub.getNumSubscribers() == 0) &&
00541        (imu_pub.getNumSubscribers() == 0) &&
00542        (mag_pub.getNumSubscribers() == 0)))
00543     return;  // why bother, no one is listening.
00544 
00545   legacynavdata_msg.header.stamp = navdata_receive_time;
00546   legacynavdata_msg.header.frame_id = drone_frame_base;
00547   legacynavdata_msg.batteryPercent = navdata_raw.navdata_demo.vbat_flying_percentage;
00548   legacynavdata_msg.state = (navdata_raw.navdata_demo.ctrl_state >> 16);
00549 
00550   // positive means counterclockwise rotation around axis
00551   legacynavdata_msg.rotX = navdata_raw.navdata_demo.phi / 1000.0;  // tilt left/right
00552   legacynavdata_msg.rotY = -navdata_raw.navdata_demo.theta / 1000.0;  // tilt forward/backward
00553   legacynavdata_msg.rotZ = -navdata_raw.navdata_demo.psi / 1000.0;  // orientation
00554 
00555   legacynavdata_msg.altd = navdata_raw.navdata_demo.altitude;  // cm
00556   legacynavdata_msg.vx = navdata_raw.navdata_demo.vx;  // mm/sec
00557   legacynavdata_msg.vy = -navdata_raw.navdata_demo.vy;  // mm/sec
00558   legacynavdata_msg.vz = -navdata_raw.navdata_demo.vz;  // mm/sec
00559   // msg.tm = navdata_raw.navdata_time.time;
00560   // First 21 bits (LSB) are usecs + 11 HSB are seconds
00561   legacynavdata_msg.tm = (navdata_raw.navdata_time.time & 0x001FFFFF) + (navdata_raw.navdata_time.time >> 21) * 1000000;
00562   legacynavdata_msg.ax = navdata_raw.navdata_phys_measures.phys_accs[ACC_X] / 1000.0;  // g
00563   legacynavdata_msg.ay = -navdata_raw.navdata_phys_measures.phys_accs[ACC_Y] / 1000.0;  // g
00564   legacynavdata_msg.az = -navdata_raw.navdata_phys_measures.phys_accs[ACC_Z] / 1000.0;  // g
00565 
00566   legacynavdata_msg.motor1 = navdata_raw.navdata_pwm.motor1;
00567   legacynavdata_msg.motor2 = navdata_raw.navdata_pwm.motor2;
00568   legacynavdata_msg.motor3 = navdata_raw.navdata_pwm.motor3;
00569   legacynavdata_msg.motor4 = navdata_raw.navdata_pwm.motor4;
00570 
00571   // New stuff
00572 
00573   if (IS_ARDRONE2)
00574   {
00575     legacynavdata_msg.magX = (int32_t)navdata_raw.navdata_magneto.mx;
00576     legacynavdata_msg.magY = (int32_t)navdata_raw.navdata_magneto.my;
00577     legacynavdata_msg.magZ = (int32_t)navdata_raw.navdata_magneto.mz;
00578 
00579     legacynavdata_msg.pressure = navdata_raw.navdata_pressure_raw.Pression_meas;  // typo in the SDK!
00580     legacynavdata_msg.temp = navdata_raw.navdata_pressure_raw.Temperature_meas;
00581 
00582     legacynavdata_msg.wind_speed = navdata_raw.navdata_wind_speed.wind_speed;
00583     legacynavdata_msg.wind_angle = navdata_raw.navdata_wind_speed.wind_angle;
00584     legacynavdata_msg.wind_comp_angle = navdata_raw.navdata_wind_speed.wind_compensation_phi;
00585   }
00586   else
00587   {
00588     legacynavdata_msg.magX = legacynavdata_msg.magY = legacynavdata_msg.magZ = 0;
00589     legacynavdata_msg.pressure = 0.0;
00590     legacynavdata_msg.temp = 0.0;
00591     legacynavdata_msg.wind_speed = 0.0;
00592     legacynavdata_msg.wind_angle = 0.0;
00593     legacynavdata_msg.wind_comp_angle = 0.0;
00594   }
00595 
00596   // Tag Detection, need to clear vectors first because it's a member variable now
00597   legacynavdata_msg.tags_type.clear();
00598   legacynavdata_msg.tags_xc.clear();
00599   legacynavdata_msg.tags_yc.clear();
00600   legacynavdata_msg.tags_width.clear();
00601   legacynavdata_msg.tags_height.clear();
00602   legacynavdata_msg.tags_orientation.clear();
00603   legacynavdata_msg.tags_distance.clear();
00604 
00605   legacynavdata_msg.tags_count = navdata_raw.navdata_vision_detect.nb_detected;
00606   for (int i = 0; i < navdata_raw.navdata_vision_detect.nb_detected; i++)
00607   {
00608     /*
00609      * The tags_type is in raw format. In order to extract the information
00610      * macros from ardrone_api.h is needed.
00611      *
00612      * #define DETECTION_MAKE_TYPE(source,tag) ( ((source)<<16) | (tag) )
00613      * #define DETECTION_EXTRACT_SOURCE(type)  ( ((type)>>16) & 0x0FF )
00614      * #define DETECTION_EXTRACT_TAG(type)     ( (type) & 0x0FF )
00615      *
00616      * Please also note that the xc, yc, width and height are in [0,1000] range
00617      * and must get converted back based on image resolution.
00618      */
00619     legacynavdata_msg.tags_type.push_back(navdata_raw.navdata_vision_detect.type[i]);
00620     legacynavdata_msg.tags_xc.push_back(navdata_raw.navdata_vision_detect.xc[i]);
00621     legacynavdata_msg.tags_yc.push_back(navdata_raw.navdata_vision_detect.yc[i]);
00622     legacynavdata_msg.tags_width.push_back(navdata_raw.navdata_vision_detect.width[i]);
00623     legacynavdata_msg.tags_height.push_back(navdata_raw.navdata_vision_detect.height[i]);
00624     legacynavdata_msg.tags_orientation.push_back(navdata_raw.navdata_vision_detect.orientation_angle[i]);
00625     legacynavdata_msg.tags_distance.push_back(navdata_raw.navdata_vision_detect.dist[i]);
00626   }
00627 
00628   /* IMU */
00629   imu_msg.header.frame_id = drone_frame_base;
00630   imu_msg.header.stamp = navdata_receive_time;
00631 
00632   // IMU - Linear Acc
00633   imu_msg.linear_acceleration.x = legacynavdata_msg.ax * 9.8;
00634   imu_msg.linear_acceleration.y = legacynavdata_msg.ay * 9.8;
00635   imu_msg.linear_acceleration.z = legacynavdata_msg.az * 9.8;
00636 
00637   // IMU - Rotation Matrix
00638   tf::Quaternion q;
00639   q.setRPY(legacynavdata_msg.rotX * _DEG2RAD, legacynavdata_msg.rotY * _DEG2RAD, legacynavdata_msg.rotZ * _DEG2RAD);
00640   tf::quaternionTFToMsg(q, imu_msg.orientation);
00641 
00642   // IMU - Gyro (Gyro is being sent in deg/sec)
00643   // TODO(mani-monaj): Should Gyro be added to Navdata?
00644   imu_msg.angular_velocity.x = navdata_raw.navdata_phys_measures.phys_gyros[GYRO_X] * DEG_TO_RAD;
00645   imu_msg.angular_velocity.y = -navdata_raw.navdata_phys_measures.phys_gyros[GYRO_Y] * DEG_TO_RAD;
00646   imu_msg.angular_velocity.z = -navdata_raw.navdata_phys_measures.phys_gyros[GYRO_Z] * DEG_TO_RAD;
00647 
00648   mag_msg.header.frame_id = drone_frame_base;
00649   mag_msg.header.stamp = navdata_receive_time;
00650   const float mag_normalizer = sqrt(legacynavdata_msg.magX * legacynavdata_msg.magX +
00651                                     legacynavdata_msg.magY * legacynavdata_msg.magY +
00652                                     legacynavdata_msg.magZ * legacynavdata_msg.magZ);
00653 
00654   // TODO(mani-monaj): Check if it is really needed that magnetometer message includes normalized value
00655   if (fabs(mag_normalizer) > 1e-9f)
00656   {
00657     mag_msg.vector.x = legacynavdata_msg.magX / mag_normalizer;
00658     mag_msg.vector.y = legacynavdata_msg.magY / mag_normalizer;
00659     mag_msg.vector.z = legacynavdata_msg.magZ / mag_normalizer;
00660     mag_pub.publish(mag_msg);
00661   }
00662   else
00663   {
00664     ROS_WARN_THROTTLE(30, "There is something wrong with the magnetometer readings (Magnitude is extremely small).");
00665   }
00666 
00667   navdata_pub.publish(legacynavdata_msg);
00668   imu_pub.publish(imu_msg);
00669 }
00670 
00671 // Load actual auto-generated code to publish full navdata
00672 #define NAVDATA_STRUCTS_SOURCE
00673 #include <ardrone_autonomy/NavdataMessageDefinitions.h>
00674 #undef NAVDATA_STRUCTS_SOURCE
00675 
00676 void ARDroneDriver::PublishTF()
00677 {
00678   tf_base_front.stamp_ = ros::Time::now();
00679   tf_base_bottom.stamp_ = ros::Time::now();
00680   tf_broad.sendTransform(tf_base_front);
00681   tf_broad.sendTransform(tf_base_bottom);
00682 }
00683 
00684 void ARDroneDriver::PublishOdometry(const navdata_unpacked_t &navdata_raw, const ros::Time &navdata_receive_time)
00685 {
00686   if (last_receive_time.isValid())
00687   {
00688     double delta_t = (navdata_receive_time - last_receive_time).toSec();
00689     odometry[0] += ((cos((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
00690                      navdata_raw.navdata_demo.vx - sin((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
00691                      -navdata_raw.navdata_demo.vy) * delta_t) / 1000.0;
00692     odometry[1] += ((sin((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
00693                      navdata_raw.navdata_demo.vx + cos((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
00694                      -navdata_raw.navdata_demo.vy) * delta_t) / 1000.0;
00695   }
00696   last_receive_time = navdata_receive_time;
00697 
00698   nav_msgs::Odometry odo_msg;
00699   odo_msg.header.stamp = navdata_receive_time;
00700   odo_msg.header.frame_id = "odom";
00701   odo_msg.child_frame_id = drone_frame_base;
00702 
00703   odo_msg.pose.pose.position.x = odometry[0];
00704   odo_msg.pose.pose.position.y = odometry[1];
00705   odo_msg.pose.pose.position.z = navdata_raw.navdata_demo.altitude / 1000.0;
00706   odo_msg.pose.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(
00707         navdata_raw.navdata_demo.phi / 180000.0 * M_PI,
00708         -navdata_raw.navdata_demo.theta / 180000.0 * M_PI,
00709         -navdata_raw.navdata_demo.psi / 180000.0 * M_PI);
00710 
00711   odo_msg.twist.twist.linear.x = navdata_raw.navdata_demo.vx / 1000.0;
00712   odo_msg.twist.twist.linear.y = -navdata_raw.navdata_demo.vy / 1000.0;
00713   odo_msg.twist.twist.linear.z = -navdata_raw.navdata_demo.vz / 1000.0;
00714 
00715   if (odo_pub.getNumSubscribers() > 0)
00716   {
00717     odo_pub.publish(odo_msg);
00718   }
00719 
00720   tf::Vector3 t;
00721   tf::pointMsgToTF(odo_msg.pose.pose.position, t);
00722   tf::Quaternion q;
00723   tf::quaternionMsgToTF(odo_msg.pose.pose.orientation, q);
00724 
00725   tf_odom.stamp_ = navdata_receive_time;
00726   tf_odom.child_frame_id_ = drone_frame_base;
00727   tf_odom.setOrigin(t);
00728   tf_odom.setRotation(q);
00729   tf_broad.sendTransform(tf_odom);
00730 }
00731 
00732 void ControlCHandler(int signal)
00733 {
00734   ros::shutdown();
00735   should_exit = 1;
00736 }
00737 
00739 // custom_main
00741 
00742 // extern "C" int custom_main(int argc, char** argv)
00743 int main(int argc, char** argv)
00744 {
00745   C_RESULT res = C_FAIL;
00746   char * drone_ip_address = NULL;
00747 
00748   // We need to implement our own Signal handler instead of ROS to shutdown
00749   // the SDK threads correctly.
00750 
00751   ros::init(argc, argv, "ardrone_driver", ros::init_options::NoSigintHandler);
00752 
00753   signal(SIGABRT, &ControlCHandler);
00754   signal(SIGTERM, &ControlCHandler);
00755   signal(SIGINT, &ControlCHandler);
00756 
00757   // Now to setup the drone and communication channels
00758   // We do this here because calling ardrone_tool_main uses an old
00759   // function initialization and is no longer recommended by parrot
00760   // I've based this section off the ControlEngine's initialization
00761   // routine (distributed with ARDrone SDK 2.0 Examples) as well as
00762   // the ardrone_tool_main function
00763 
00764   // Parse command line for
00765   // Backward compatibility with `-ip` command line argument
00766   argc--;
00767   argv++;
00768   while (argc && *argv[0] == '-')
00769   {
00770     if (!strcmp(*argv, "-ip") && (argc > 1))
00771     {
00772       drone_ip_address = *(argv + 1);
00773       printf("Using custom ip address %s\n", drone_ip_address);
00774       argc--;
00775       argv++;
00776     }
00777     argc--;
00778     argv++;
00779   }
00780 
00781   // Configure wifi
00782   vp_com_wifi_config_t *config = reinterpret_cast<vp_com_wifi_config_t*>(wifi_config());
00783 
00784   if (config)
00785   {
00786     vp_os_memset(&wifi_ardrone_ip[0], 0, ARDRONE_IPADDRESS_SIZE);
00787 
00788     // TODO(mani-monaj): Check if IP is valid
00789     if (drone_ip_address)
00790     {
00791       printf("===================+> %s\n", drone_ip_address);
00792       strncpy(&wifi_ardrone_ip[0], drone_ip_address, ARDRONE_IPADDRESS_SIZE - 1);
00793     }
00794     else
00795     {
00796       printf("===================+> %s\n", config->server);
00797       strncpy(&wifi_ardrone_ip[0], config->server, ARDRONE_IPADDRESS_SIZE - 1);
00798     }
00799   }
00800 
00801   while (-1 == getDroneVersion(".", wifi_ardrone_ip, &ardroneVersion))
00802   {
00803     printf("Getting AR.Drone version ...\n");
00804     vp_os_delay(250);
00805   }
00806 
00807   // Setup communication channels
00808   res = ardrone_tool_setup_com(NULL);
00809   if (FAILED(res))
00810   {
00811     PRINT("Wifi initialization failed. It means either:\n");
00812     PRINT("\t* you're not root (it's mandatory because you can set up wifi connection only as root)\n");
00813     PRINT("\t* wifi device is not present (on your pc or on your card)\n");
00814     PRINT("\t* you set the wrong name for wifi interface (for example rausb0 instead of wlan0) \n");
00815     PRINT("\t* ap is not up (reboot card or remove wifi usb dongle)\n");
00816     PRINT("\t* wifi device has no antenna\n");
00817   }
00818   else
00819   {
00820     // setup the application and user profiles for the driver
00821     const char* appname = reinterpret_cast<const char*>(DRIVER_APPNAME);
00822     const char* usrname = reinterpret_cast<const char*>(DRIVER_USERNAME);
00823     ardrone_gen_appid(appname, "2.0", app_id, app_name, APPLI_NAME_SIZE);
00824     ardrone_gen_usrid(usrname, usr_id, usr_name, USER_NAME_SIZE);
00825 
00826     // and finally initialize everything!
00827     // this will then call our sdk, which then starts the ::run() method of this file as an ardrone client thread
00828 
00829     res = ardrone_tool_init(wifi_ardrone_ip,
00830                             strlen(wifi_ardrone_ip),
00831                             NULL,
00832                             app_name,
00833                             usr_name,
00834                             NULL,
00835                             NULL,
00836                             MAX_FLIGHT_STORING_SIZE,
00837                             NULL);
00838 
00839     while (SUCCEED(res) && ardrone_tool_exit() == FALSE)
00840     {
00841       res = ardrone_tool_update();
00842     }
00843     res = ardrone_tool_shutdown();
00844   }
00845   return SUCCEED(res) ? 0 : -1;
00846 }


ardrone_autonomy
Author(s): Mani Monajjemi, Mani Monajjemi
autogenerated on Fri Dec 9 2016 03:36:59