ardrone_driver.cpp
Go to the documentation of this file.
1 
25 #include <signal.h>
26 #include <string>
27 #include <algorithm>
28 #include <vector>
29 
32 #include <ardrone_autonomy/video.h>
33 
34 
36 // class ARDroneDriver
38 
40  : private_nh("~"),
41  image_transport(node_handle),
42  // Ugly: This has been defined in the template file. Cleaner way to guarantee initilaztion?
43  initialized_navdata_publishers(false),
44  last_frame_id(-1),
45  last_navdata_id(-1),
46  is_inited(false),
47  last_receive_time(0.0)
48 {
50  takeoff_sub = node_handle.subscribe("ardrone/takeoff", 1, &TakeoffCallback);
51  reset_sub = node_handle.subscribe("ardrone/reset", 1, &ResetCallback);
52  land_sub = node_handle.subscribe("ardrone/land", 1, &LandCallback);
53  image_pub = image_transport.advertiseCamera("ardrone/image_raw", 10);
54  hori_pub = image_transport.advertiseCamera("ardrone/front/image_raw", 10);
55  vert_pub = image_transport.advertiseCamera("ardrone/bottom/image_raw", 10);
62 
63  /* TF Frames */
64  std::string tf_prefix_key;
65  private_nh.searchParam("tf_prefix", tf_prefix_key);
66  private_nh.param(tf_prefix_key, tf_prefix, std::string(""));
67  private_nh.param<std::string>("drone_frame_id", drone_frame_id, "ardrone_base");
68  drone_frame_base = tf::resolve(tf_prefix, drone_frame_id + "_link");
69  drone_frame_imu = tf::resolve(tf_prefix, drone_frame_id + "_imu");
70  drone_frame_front_cam = tf::resolve(tf_prefix, drone_frame_id + "_frontcam");
71  drone_frame_bottom_cam = tf::resolve(tf_prefix, drone_frame_id + "_bottomcam");
73 
74  if (private_nh.hasParam("root_frame"))
75  {
76  ROS_WARN("Changing `root_frame` has been deprecated since version 1.4. ");
77  }
78 
79  // Fill constant parts of IMU Message
80  // If no rosparam is set then the default value of 0.0 will be assigned to all covariance values
81  for (int i = 0; i < 9; i++)
82  {
83  imu_msg.linear_acceleration_covariance[i] = 0.0;
84  imu_msg.angular_velocity_covariance[i] = 0.0;
85  imu_msg.orientation_covariance[i] = 0.0;
86  }
87  ReadCovParams("~cov/imu_la", imu_msg.linear_acceleration_covariance);
88  ReadCovParams("~cov/imu_av", imu_msg.angular_velocity_covariance);
89  ReadCovParams("~cov/imu_or", imu_msg.orientation_covariance);
90 
91  if (private_nh.hasParam("do_imu_caliberation"))
92  {
93  ROS_WARN("IMU Caliberation has been deprecated since 1.4.");
94  }
95 
96  // Camera Info Manager
97  cinfo_hori = new camera_info_manager::CameraInfoManager(ros::NodeHandle("ardrone/front"), "ardrone_front");
98  cinfo_vert = new camera_info_manager::CameraInfoManager(ros::NodeHandle("ardrone/bottom"), "ardrone_bottom");
99 
100  // TF Stuff
101 
102 
103  // Front Cam to Base
104  // TODO(mani-monaj): Precise values for Drone1 & Drone2
107  tf::createQuaternionFromRPY(-90.0 * _DEG2RAD, 0.0, -90.0 * _DEG2RAD),
108  tf::Vector3(0.21, 0.0, 0.0)),
109  ros::Time::now(), drone_frame_base, drone_frame_front_cam);
110 
111  // Bottom Cam to Base (Bad Assumption: No translation from IMU and Base)
112  // TODO(mani-monaj): This should be different from Drone 1 & 2.
115  tf::createQuaternionFromRPY(180.0 * _DEG2RAD, 0.0, 90.0 * _DEG2RAD),
116  tf::Vector3(0.0, -0.02, 0.0)),
117  ros::Time::now(), drone_frame_base, drone_frame_bottom_cam);
118 
119  // reset odometry
120  odometry[0] = odometry[1] = 0;
121 }
122 
124 {
125  delete cinfo_hori;
126  delete cinfo_vert;
127 }
128 
130 {
131  ros::Rate loop_rate(looprate);
132  const ros::Time startTime = ros::Time::now();
133  static int freq_dev = 0;
134  while (node_handle.ok())
135  {
136  if (!is_inited) // Give the Drone 5s of free time to finish init phase
137  {
138  if (((ros::Time::now() - startTime).toSec()) > 5.0)
139  {
140  is_inited = true;
141 
142  // Send the configuration to the drone
143  ConfigureDrone();
144 
145  vp_os_mutex_lock(&navdata_lock);
146  ROS_INFO("Successfully connected to '%s' (AR-Drone %d.0 - Firmware: %s) - Battery(%%): %d",
147  ardrone_control_config.ardrone_name,
148  (IS_ARDRONE1) ? 1 : 2,
149  ardrone_control_config.num_version_soft,
150  shared_raw_navdata_ptr->navdata_demo.vbat_flying_percentage);
151  ROS_INFO("Navdata Publish Settings:");
152  ROS_INFO(" Legacy Navdata Mode: %s", enabled_legacy_navdata ? "On" : "Off");
153  ROS_INFO(" ROS Loop Rate: %d Hz", looprate);
154  ROS_INFO(" Realtime Navdata Publish: %s", realtime_navdata ? "On" : "Off");
155  ROS_INFO(" Realtime Video Publish: %s", realtime_video ? "On" : "Off");
156  ROS_INFO(" Drone Navdata Send Speed: %s",
157  ardrone_application_default_config.navdata_demo == 0 ?
158  "200Hz (navdata_demo=0)" : "15Hz (navdata_demo=1)");
159  // TODO(mani-monaj): Enabled Navdata Demo
160  vp_os_mutex_unlock(&navdata_lock);
161  if (ardrone_control_config.num_version_soft[0] == '0')
162  {
163  ROS_WARN("The AR-Drone has a suspicious Firmware number. It usually means the network link is unreliable.");
164  }
165  ROS_DEBUG_STREAM("Using " << tf_prefix << " to prefix TF frames.");
166  }
167  }
168  else
169  {
170  if (!realtime_video)
171  {
172  vp_os_mutex_lock(&video_lock);
174  vp_os_mutex_unlock(&video_lock);
176  {
178  PublishVideo();
179  }
180  }
181 
182  if (!realtime_navdata)
183  {
184  vp_os_mutex_lock(&navdata_lock);
186  vp_os_mutex_unlock(&navdata_lock);
188  {
189  vp_os_mutex_lock(&navdata_lock);
191 
192  // Thread safe copy of interesting Navdata data
193  // TODO(mani-monaj): This is a very expensive task, can we optimize here?
194  // maybe ignoring the copy when it is not needed.
195  const navdata_unpacked_t navdata_raw = *shared_raw_navdata_ptr;
196  const ros::Time navdata_receive_time = shared_navdata_receive_time;
197  vp_os_mutex_unlock(&navdata_lock);
198 
199  // This function is defined in the template NavdataMessageDefinitions.h template file
200  PublishNavdataTypes(navdata_raw, navdata_receive_time);
201  PublishNavdata(navdata_raw, navdata_receive_time);
202  PublishOdometry(navdata_raw, navdata_receive_time);
203  }
204  }
205  if (freq_dev == 0) PublishTF();
206 
207  // (looprate / 5)Hz TF publish
208  // TODO(mani-monaj): Make TF publish rate fixed
209  freq_dev = (freq_dev + 1) % 5;
210  }
211  ros::spinOnce();
212  loop_rate.sleep();
213  }
214  printf("ROS loop terminated ... \n");
215 }
216 
218 {
220 }
221 
222 double ARDroneDriver::CalcAverage(const std::vector<double> &vec)
223 {
224  double ret = 0.0;
225  for (unsigned int i = 0; i < vec.size(); i++)
226  {
227  ret += vec[i];
228  }
229  return (ret / vec.size());
230 }
231 
232 bool ARDroneDriver::ReadCovParams(const std::string &param_name, boost::array<double, 9> &cov_array)
233 {
234  XmlRpc::XmlRpcValue cov_list;
235  std::stringstream str_stream;
236  if (ros::param::get(param_name, cov_list))
237  {
238  if (cov_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
239  {
240  ROS_WARN("Covariance values for %s is not a list", param_name.c_str());
241  return false;
242  }
243 
244  if (cov_list.size() != 9)
245  {
246  ROS_WARN("Covariance list size for %s is not of size 9 (Size: %d)", param_name.c_str(), cov_list.size());
247  return false;
248  }
249  str_stream << param_name << " set to [";
250  for (int32_t i = 0; i < cov_list.size(); i++)
251  {
252  ROS_ASSERT(cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
253  cov_array[i] = static_cast<double>(cov_list[i]);
254  str_stream << cov_array[i] << ((i < 8) ? ", " : "");
255  }
256  str_stream << "]";
257  ROS_INFO("%s", str_stream.str().c_str());
258  return true;
259  }
260  else
261  {
262  ROS_INFO("No values found for `%s` in parameters, set all to zero.", param_name.c_str());
263  return false;
264  }
265 }
266 
268 {
269  if (
270  (image_pub.getNumSubscribers() == 0) &&
271  (hori_pub.getNumSubscribers() == 0) &&
272  (vert_pub.getNumSubscribers() == 0)
273  ) return;
274 
275  // Camera Info (NO PIP)
276 
277  sensor_msgs::CameraInfo cinfo_msg_hori = cinfo_hori->getCameraInfo();
278  sensor_msgs::CameraInfo cinfo_msg_vert = cinfo_vert->getCameraInfo();
279 
280  cinfo_msg_hori.header.frame_id = drone_frame_front_cam;
281  cinfo_msg_vert.header.frame_id = drone_frame_bottom_cam;
282 
283  if (IS_ARDRONE1)
284  {
285  /*
286  * Information on buffer and image sizes.
287  * Buffer is always in QVGA size, however for different Camera Modes
288  * The picture and PIP sizes are different.
289  *
290  * image_raw and buffer are always 320x240. In order to preserve backward compatibilty image_raw remains
291  * always as before. Two new set of topics are added for two new cameras : /ardrone/front/xxx and /ardrone/bottom/xxx
292  *
293  * In Camera State 0 front image relays the buffer and image_raw and bottom image are not updated.
294  *
295  * In Camera State 1 bottom image is a 174x144 crop of the buffer. The front image is not updated
296  *
297  * In Camera State 2 bottom image is a PIP cut of size (87x72) from buffer.
298  * The bottom image is a (320-87)x(240) cut of the buffer.
299  *
300  * In Camera State 3 front image is a PIP cut of size (58x42) from buffer.
301  * The bottom image is a (174-58)x144 crop of the buffer.
302  */
303  sensor_msgs::Image image_msg;
304  sensor_msgs::Image::_data_type::iterator _it;
305 
306  if ((cam_state == ZAP_CHANNEL_HORI) || (cam_state == ZAP_CHANNEL_LARGE_HORI_SMALL_VERT))
307  {
308  image_msg.header.frame_id = drone_frame_front_cam;
309  }
310  else if ((cam_state == ZAP_CHANNEL_VERT) || (cam_state == ZAP_CHANNEL_LARGE_VERT_SMALL_HORI))
311  {
312  image_msg.header.frame_id = drone_frame_bottom_cam;
313  }
314  else
315  {
316  ROS_WARN_ONCE("Something is wrong with camera channel config.");
317  }
318 
319  image_msg.width = D1_STREAM_WIDTH;
320  image_msg.height = D1_STREAM_HEIGHT;
321  image_msg.encoding = "rgb8";
322  image_msg.is_bigendian = false;
323  image_msg.step = D1_STREAM_WIDTH * 3;
324  image_msg.data.resize(D1_STREAM_WIDTH * D1_STREAM_HEIGHT * 3);
325 
326  if (!realtime_video) vp_os_mutex_lock(&video_lock);
327  image_msg.header.stamp = shared_video_receive_time;
328  std::copy(buffer, buffer + (D1_STREAM_WIDTH * D1_STREAM_HEIGHT * 3), image_msg.data.begin());
329  if (!realtime_video) vp_os_mutex_unlock(&video_lock);
330 
331  cinfo_msg_hori.header.stamp = image_msg.header.stamp;
332  cinfo_msg_vert.header.stamp = image_msg.header.stamp;
333 
334  if (cam_state == ZAP_CHANNEL_HORI)
335  {
336  /*
337  * Horizontal camera is activated, only /ardrone/front/ is being updated
338  */
339  cinfo_msg_hori.width = D1_STREAM_WIDTH;
340  cinfo_msg_hori.height = D1_STREAM_HEIGHT;
341 
342  image_pub.publish(image_msg, cinfo_msg_hori);
343  hori_pub.publish(image_msg, cinfo_msg_hori);
344  }
345  else if (cam_state == ZAP_CHANNEL_VERT)
346  {
347  /*
348  * Vertical camera is activated, only /ardrone/bottom/ is being updated
349  */
350  image_msg.width = D1_VERTSTREAM_WIDTH;
351  image_msg.height = D1_VERTSTREAM_HEIGHT;
352  image_msg.encoding = "rgb8";
353  image_msg.is_bigendian = false;
354  image_msg.step = D1_VERTSTREAM_WIDTH * 3;
355  image_msg.data.clear();
356  image_msg.data.resize(D1_VERTSTREAM_WIDTH * D1_VERTSTREAM_HEIGHT * 3);
357  _it = image_msg.data.begin();
358  if (!realtime_video) vp_os_mutex_lock(&video_lock);
359  for (int row = 0; row < D1_VERTSTREAM_HEIGHT ; row++)
360  {
361  int _b = row * D1_STREAM_WIDTH * 3;
362  int _e = _b + image_msg.step;
363  _it = std::copy(buffer + _b, buffer + _e, _it);
364  }
365  if (!realtime_video) vp_os_mutex_unlock(&video_lock);
366 
367  cinfo_msg_vert.width = D1_VERTSTREAM_WIDTH;
368  cinfo_msg_vert.height = D1_VERTSTREAM_HEIGHT;
369  image_pub.publish(image_msg, cinfo_msg_vert);
370  vert_pub.publish(image_msg, cinfo_msg_vert);
371  }
372  else if (cam_state == ZAP_CHANNEL_LARGE_HORI_SMALL_VERT)
373  {
374  /*
375  * The Picture in Picture is activated with vertical camera inside the horizontal
376  * camera. Both /ardrone/front and /ardrone/bottom is being updated
377  */
378 
379  // Front (Cropping the first 88 columns)
380  image_msg.width = D1_STREAM_WIDTH - D1_MODE2_PIP_WIDTH;
381  image_msg.height = D1_STREAM_HEIGHT;
382  image_msg.encoding = "rgb8";
383  image_msg.is_bigendian = false;
384  image_msg.step = (D1_STREAM_WIDTH - D1_MODE2_PIP_WIDTH) * 3;
385  image_msg.data.clear();
386  image_msg.data.resize((D1_STREAM_WIDTH - D1_MODE2_PIP_WIDTH)*D1_STREAM_HEIGHT * 3);
387  _it = image_msg.data.begin();
388  if (!realtime_video) vp_os_mutex_lock(&video_lock);
389  for (int row = 0; row < D1_STREAM_HEIGHT; row++)
390  {
391  int _b = (row * D1_STREAM_WIDTH * 3) + (D1_MODE2_PIP_WIDTH * 3);
392  int _e = _b + image_msg.step;
393  _it = std::copy(buffer + _b, buffer + _e, _it);
394  }
395  if (!realtime_video) vp_os_mutex_unlock(&video_lock);
396 
397  cinfo_msg_hori.width = D1_STREAM_WIDTH - D1_MODE2_PIP_WIDTH;
398  cinfo_msg_hori.height = D1_STREAM_HEIGHT;
399  hori_pub.publish(image_msg, cinfo_msg_hori);
400 
401  // Bottom
402  image_msg.width = D1_MODE2_PIP_WIDTH;
403  image_msg.height = D1_MODE2_PIP_HEIGHT;
404  image_msg.encoding = "rgb8";
405  image_msg.is_bigendian = false;
406  image_msg.step = D1_MODE2_PIP_WIDTH * 3;
407  image_msg.data.clear();
408  image_msg.data.resize(D1_MODE2_PIP_WIDTH * D1_MODE2_PIP_HEIGHT * 3);
409  _it = image_msg.data.begin();
410  if (!realtime_video) vp_os_mutex_lock(&video_lock);
411  for (int row = 0; row < D1_MODE2_PIP_HEIGHT; row++)
412  {
413  int _b = row * D1_STREAM_WIDTH * 3;
414  int _e = _b + image_msg.step;
415  _it = std::copy(buffer + _b, buffer + _e, _it);
416  }
417  if (!realtime_video) vp_os_mutex_unlock(&video_lock);
418 
419  cinfo_msg_vert.width = D1_MODE2_PIP_WIDTH;
420  cinfo_msg_vert.height = D1_MODE2_PIP_HEIGHT;
421  vert_pub.publish(image_msg, cinfo_msg_vert);
422  }
423  else if (cam_state == ZAP_CHANNEL_LARGE_VERT_SMALL_HORI)
424  {
425  /*
426  * The Picture in Picture is activated with horizontal camera inside the vertical
427  * camera. Both /ardrone/front and /ardrone/bottom is being updated
428  */
429 
430  // Bottom (Cropping the first 58 columns)
431  image_msg.width = D1_VERTSTREAM_WIDTH - D1_MODE3_PIP_WIDTH;
432  image_msg.height = D1_VERTSTREAM_HEIGHT;
433  image_msg.encoding = "rgb8";
434  image_msg.is_bigendian = false;
435  image_msg.step = (D1_VERTSTREAM_WIDTH - D1_MODE3_PIP_WIDTH) * 3;
436  image_msg.data.clear();
437  image_msg.data.resize((D1_VERTSTREAM_WIDTH - D1_MODE3_PIP_WIDTH)* D1_VERTSTREAM_HEIGHT * 3);
438  _it = image_msg.data.begin();
439  for (int row = 0; row < D1_VERTSTREAM_HEIGHT; row++)
440  {
441  int _b = (row * (D1_STREAM_WIDTH * 3)) + (D1_MODE3_PIP_WIDTH * 3);
442  int _e = _b + image_msg.step;
443  if (!realtime_video) vp_os_mutex_lock(&video_lock);
444  _it = std::copy(buffer + _b, buffer + _e, _it);
445  if (!realtime_video) vp_os_mutex_unlock(&video_lock);
446  }
447 
448  cinfo_msg_vert.width = D1_VERTSTREAM_WIDTH - D1_MODE3_PIP_WIDTH;
449  cinfo_msg_vert.height = D1_VERTSTREAM_HEIGHT;
450  vert_pub.publish(image_msg, cinfo_msg_vert);
451 
452  // Front
453  image_msg.width = D1_MODE3_PIP_WIDTH;
454  image_msg.height = D1_MODE3_PIP_HEIGHT;
455  image_msg.encoding = "rgb8";
456  image_msg.is_bigendian = false;
457  image_msg.step = D1_MODE3_PIP_WIDTH * 3;
458  image_msg.data.clear();
459  image_msg.data.resize(D1_MODE3_PIP_WIDTH * D1_MODE3_PIP_HEIGHT * 3);
460  _it = image_msg.data.begin();
461  if (!realtime_video) vp_os_mutex_lock(&video_lock);
462  for (int row = 0; row < D1_MODE3_PIP_HEIGHT; row++)
463  {
464  int _b = row * D1_STREAM_WIDTH * 3;
465  int _e = _b + image_msg.step;
466  _it = std::copy(buffer + _b, buffer + _e, _it);
467  }
468  if (!realtime_video) vp_os_mutex_unlock(&video_lock);
469 
470  cinfo_msg_hori.width = D1_MODE3_PIP_WIDTH;
471  cinfo_msg_hori.height = D1_MODE3_PIP_HEIGHT;
472  hori_pub.publish(image_msg, cinfo_msg_hori);
473  }
474  }
475 
481  if (IS_ARDRONE2)
482  {
483  sensor_msgs::Image image_msg;
484  sensor_msgs::Image::_data_type::iterator _it;
485 
486  if (cam_state == ZAP_CHANNEL_HORI)
487  {
488  image_msg.header.frame_id = drone_frame_front_cam;
489  }
490  else if (cam_state == ZAP_CHANNEL_VERT)
491  {
492  image_msg.header.frame_id = drone_frame_bottom_cam;
493  }
494  else
495  {
496  ROS_WARN_ONCE("Something is wrong with camera channel config.");
497  }
498 
499  image_msg.width = D2_STREAM_WIDTH;
500  image_msg.height = D2_STREAM_HEIGHT;
501  image_msg.encoding = "rgb8";
502  image_msg.is_bigendian = false;
503  image_msg.step = D2_STREAM_WIDTH * 3;
504  image_msg.data.resize(D2_STREAM_WIDTH * D2_STREAM_HEIGHT * 3);
505  if (!realtime_video) vp_os_mutex_lock(&video_lock);
506  image_msg.header.stamp = shared_video_receive_time;
507  std::copy(buffer, buffer + (D2_STREAM_WIDTH * D2_STREAM_HEIGHT * 3), image_msg.data.begin());
508  if (!realtime_video) vp_os_mutex_unlock(&video_lock);
509  // We only put the width and height in here.
510 
511  cinfo_msg_hori.header.stamp = image_msg.header.stamp;
512  cinfo_msg_vert.header.stamp = image_msg.header.stamp;
513 
514  if (cam_state == ZAP_CHANNEL_HORI)
515  {
516  /*
517  * Horizontal camera is activated, only /ardrone/front/ is being updated
518  */
519  cinfo_msg_hori.width = D2_STREAM_WIDTH;
520  cinfo_msg_hori.height = D2_STREAM_HEIGHT;
521  image_pub.publish(image_msg, cinfo_msg_hori); // /ardrone
522  hori_pub.publish(image_msg, cinfo_msg_hori);
523  }
524  else if (cam_state == ZAP_CHANNEL_VERT)
525  {
526  /*
527  * Vertical camera is activated, only /ardrone/bottom/ is being updated
528  */
529  cinfo_msg_vert.width = D2_STREAM_WIDTH;
530  cinfo_msg_vert.height = D2_STREAM_HEIGHT;
531  image_pub.publish(image_msg, cinfo_msg_vert); // /ardrone
532  vert_pub.publish(image_msg, cinfo_msg_vert);
533  }
534  }
535 }
536 
537 void ARDroneDriver::PublishNavdata(const navdata_unpacked_t &navdata_raw, const ros::Time &navdata_receive_time)
538 {
539  if (!enabled_legacy_navdata ||
540  ((navdata_pub.getNumSubscribers() == 0) &&
541  (imu_pub.getNumSubscribers() == 0) &&
542  (mag_pub.getNumSubscribers() == 0)))
543  return; // why bother, no one is listening.
544 
545  legacynavdata_msg.header.stamp = navdata_receive_time;
546  legacynavdata_msg.header.frame_id = drone_frame_base;
547  legacynavdata_msg.batteryPercent = navdata_raw.navdata_demo.vbat_flying_percentage;
548  legacynavdata_msg.state = (navdata_raw.navdata_demo.ctrl_state >> 16);
549 
550  // positive means counterclockwise rotation around axis
551  legacynavdata_msg.rotX = navdata_raw.navdata_demo.phi / 1000.0; // tilt left/right
552  legacynavdata_msg.rotY = -navdata_raw.navdata_demo.theta / 1000.0; // tilt forward/backward
553  legacynavdata_msg.rotZ = -navdata_raw.navdata_demo.psi / 1000.0; // orientation
554 
555  legacynavdata_msg.altd = navdata_raw.navdata_demo.altitude; // cm
556  legacynavdata_msg.vx = navdata_raw.navdata_demo.vx; // mm/sec
557  legacynavdata_msg.vy = -navdata_raw.navdata_demo.vy; // mm/sec
558  legacynavdata_msg.vz = -navdata_raw.navdata_demo.vz; // mm/sec
559  // msg.tm = navdata_raw.navdata_time.time;
560  // First 21 bits (LSB) are usecs + 11 HSB are seconds
561  legacynavdata_msg.tm = (navdata_raw.navdata_time.time & 0x001FFFFF) + (navdata_raw.navdata_time.time >> 21) * 1000000;
562  legacynavdata_msg.ax = navdata_raw.navdata_phys_measures.phys_accs[ACC_X] / 1000.0; // g
563  legacynavdata_msg.ay = -navdata_raw.navdata_phys_measures.phys_accs[ACC_Y] / 1000.0; // g
564  legacynavdata_msg.az = -navdata_raw.navdata_phys_measures.phys_accs[ACC_Z] / 1000.0; // g
565 
566  legacynavdata_msg.motor1 = navdata_raw.navdata_pwm.motor1;
567  legacynavdata_msg.motor2 = navdata_raw.navdata_pwm.motor2;
568  legacynavdata_msg.motor3 = navdata_raw.navdata_pwm.motor3;
569  legacynavdata_msg.motor4 = navdata_raw.navdata_pwm.motor4;
570 
571  // New stuff
572 
573  if (IS_ARDRONE2)
574  {
575  legacynavdata_msg.magX = (int32_t)navdata_raw.navdata_magneto.mx;
576  legacynavdata_msg.magY = (int32_t)navdata_raw.navdata_magneto.my;
577  legacynavdata_msg.magZ = (int32_t)navdata_raw.navdata_magneto.mz;
578 
579  legacynavdata_msg.pressure = navdata_raw.navdata_pressure_raw.Pression_meas; // typo in the SDK!
580  legacynavdata_msg.temp = navdata_raw.navdata_pressure_raw.Temperature_meas;
581 
582  legacynavdata_msg.wind_speed = navdata_raw.navdata_wind_speed.wind_speed;
583  legacynavdata_msg.wind_angle = navdata_raw.navdata_wind_speed.wind_angle;
584  legacynavdata_msg.wind_comp_angle = navdata_raw.navdata_wind_speed.wind_compensation_phi;
585  }
586  else
587  {
589  legacynavdata_msg.pressure = 0.0;
590  legacynavdata_msg.temp = 0.0;
591  legacynavdata_msg.wind_speed = 0.0;
592  legacynavdata_msg.wind_angle = 0.0;
593  legacynavdata_msg.wind_comp_angle = 0.0;
594  }
595 
596  // Tag Detection, need to clear vectors first because it's a member variable now
597  legacynavdata_msg.tags_type.clear();
598  legacynavdata_msg.tags_xc.clear();
599  legacynavdata_msg.tags_yc.clear();
600  legacynavdata_msg.tags_width.clear();
601  legacynavdata_msg.tags_height.clear();
602  legacynavdata_msg.tags_orientation.clear();
603  legacynavdata_msg.tags_distance.clear();
604 
605  legacynavdata_msg.tags_count = navdata_raw.navdata_vision_detect.nb_detected;
606  for (int i = 0; i < navdata_raw.navdata_vision_detect.nb_detected; i++)
607  {
608  /*
609  * The tags_type is in raw format. In order to extract the information
610  * macros from ardrone_api.h is needed.
611  *
612  * #define DETECTION_MAKE_TYPE(source,tag) ( ((source)<<16) | (tag) )
613  * #define DETECTION_EXTRACT_SOURCE(type) ( ((type)>>16) & 0x0FF )
614  * #define DETECTION_EXTRACT_TAG(type) ( (type) & 0x0FF )
615  *
616  * Please also note that the xc, yc, width and height are in [0,1000] range
617  * and must get converted back based on image resolution.
618  */
619  legacynavdata_msg.tags_type.push_back(navdata_raw.navdata_vision_detect.type[i]);
620  legacynavdata_msg.tags_xc.push_back(navdata_raw.navdata_vision_detect.xc[i]);
621  legacynavdata_msg.tags_yc.push_back(navdata_raw.navdata_vision_detect.yc[i]);
622  legacynavdata_msg.tags_width.push_back(navdata_raw.navdata_vision_detect.width[i]);
623  legacynavdata_msg.tags_height.push_back(navdata_raw.navdata_vision_detect.height[i]);
624  legacynavdata_msg.tags_orientation.push_back(navdata_raw.navdata_vision_detect.orientation_angle[i]);
625  legacynavdata_msg.tags_distance.push_back(navdata_raw.navdata_vision_detect.dist[i]);
626  }
627 
628  /* IMU */
629  imu_msg.header.frame_id = drone_frame_base;
630  imu_msg.header.stamp = navdata_receive_time;
631 
632  // IMU - Linear Acc
633  imu_msg.linear_acceleration.x = legacynavdata_msg.ax * 9.8;
634  imu_msg.linear_acceleration.y = legacynavdata_msg.ay * 9.8;
635  imu_msg.linear_acceleration.z = legacynavdata_msg.az * 9.8;
636 
637  // IMU - Rotation Matrix
638  tf::Quaternion q;
640  tf::quaternionTFToMsg(q, imu_msg.orientation);
641 
642  // IMU - Gyro (Gyro is being sent in deg/sec)
643  // TODO(mani-monaj): Should Gyro be added to Navdata?
644  imu_msg.angular_velocity.x = navdata_raw.navdata_phys_measures.phys_gyros[GYRO_X] * DEG_TO_RAD;
645  imu_msg.angular_velocity.y = -navdata_raw.navdata_phys_measures.phys_gyros[GYRO_Y] * DEG_TO_RAD;
646  imu_msg.angular_velocity.z = -navdata_raw.navdata_phys_measures.phys_gyros[GYRO_Z] * DEG_TO_RAD;
647 
648  mag_msg.header.frame_id = drone_frame_base;
649  mag_msg.header.stamp = navdata_receive_time;
650  const float mag_normalizer = sqrt(legacynavdata_msg.magX * legacynavdata_msg.magX +
653 
654  // TODO(mani-monaj): Check if it is really needed that magnetometer message includes normalized value
655  if (fabs(mag_normalizer) > 1e-9f)
656  {
657  mag_msg.vector.x = legacynavdata_msg.magX / mag_normalizer;
658  mag_msg.vector.y = legacynavdata_msg.magY / mag_normalizer;
659  mag_msg.vector.z = legacynavdata_msg.magZ / mag_normalizer;
661  }
662  else
663  {
664  ROS_WARN_THROTTLE(30, "There is something wrong with the magnetometer readings (Magnitude is extremely small).");
665  }
666 
669 }
670 
671 // Load actual auto-generated code to publish full navdata
672 #define NAVDATA_STRUCTS_SOURCE
674 #undef NAVDATA_STRUCTS_SOURCE
675 
677 {
682 }
683 
684 void ARDroneDriver::PublishOdometry(const navdata_unpacked_t &navdata_raw, const ros::Time &navdata_receive_time)
685 {
687  {
688  double delta_t = (navdata_receive_time - last_receive_time).toSec();
689  odometry[0] += ((cos((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
690  navdata_raw.navdata_demo.vx - sin((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
691  -navdata_raw.navdata_demo.vy) * delta_t) / 1000.0;
692  odometry[1] += ((sin((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
693  navdata_raw.navdata_demo.vx + cos((navdata_raw.navdata_demo.psi / 180000.0) * M_PI) *
694  -navdata_raw.navdata_demo.vy) * delta_t) / 1000.0;
695  }
696  last_receive_time = navdata_receive_time;
697 
698  nav_msgs::Odometry odo_msg;
699  odo_msg.header.stamp = navdata_receive_time;
700  odo_msg.header.frame_id = "odom";
701  odo_msg.child_frame_id = drone_frame_base;
702 
703  odo_msg.pose.pose.position.x = odometry[0];
704  odo_msg.pose.pose.position.y = odometry[1];
705  odo_msg.pose.pose.position.z = navdata_raw.navdata_demo.altitude / 1000.0;
706  odo_msg.pose.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(
707  navdata_raw.navdata_demo.phi / 180000.0 * M_PI,
708  -navdata_raw.navdata_demo.theta / 180000.0 * M_PI,
709  -navdata_raw.navdata_demo.psi / 180000.0 * M_PI);
710 
711  odo_msg.twist.twist.linear.x = navdata_raw.navdata_demo.vx / 1000.0;
712  odo_msg.twist.twist.linear.y = -navdata_raw.navdata_demo.vy / 1000.0;
713  odo_msg.twist.twist.linear.z = -navdata_raw.navdata_demo.vz / 1000.0;
714 
715  if (odo_pub.getNumSubscribers() > 0)
716  {
717  odo_pub.publish(odo_msg);
718  }
719 
720  tf::Vector3 t;
721  tf::pointMsgToTF(odo_msg.pose.pose.position, t);
722  tf::Quaternion q;
723  tf::quaternionMsgToTF(odo_msg.pose.pose.orientation, q);
724 
725  tf_odom.stamp_ = navdata_receive_time;
727  tf_odom.setOrigin(t);
728  tf_odom.setRotation(q);
730 }
731 
732 void ControlCHandler(int signal)
733 {
734  ros::shutdown();
735  should_exit = 1;
736 }
737 
739 // custom_main
741 
742 // extern "C" int custom_main(int argc, char** argv)
743 int main(int argc, char** argv)
744 {
745  C_RESULT res = C_FAIL;
746  char * drone_ip_address = NULL;
747 
748  // We need to implement our own Signal handler instead of ROS to shutdown
749  // the SDK threads correctly.
750 
751  ros::init(argc, argv, "ardrone_driver", ros::init_options::NoSigintHandler);
752 
753  signal(SIGABRT, &ControlCHandler);
754  signal(SIGTERM, &ControlCHandler);
755  signal(SIGINT, &ControlCHandler);
756 
757  // Now to setup the drone and communication channels
758  // We do this here because calling ardrone_tool_main uses an old
759  // function initialization and is no longer recommended by parrot
760  // I've based this section off the ControlEngine's initialization
761  // routine (distributed with ARDrone SDK 2.0 Examples) as well as
762  // the ardrone_tool_main function
763 
764  // Parse command line for
765  // Backward compatibility with `-ip` command line argument
766  argc--;
767  argv++;
768  while (argc && *argv[0] == '-')
769  {
770  if (!strcmp(*argv, "-ip") && (argc > 1))
771  {
772  drone_ip_address = *(argv + 1);
773  printf("Using custom ip address %s\n", drone_ip_address);
774  argc--;
775  argv++;
776  }
777  argc--;
778  argv++;
779  }
780 
781  // Configure wifi
782  vp_com_wifi_config_t *config = reinterpret_cast<vp_com_wifi_config_t*>(wifi_config());
783 
784  if (config)
785  {
786  vp_os_memset(&wifi_ardrone_ip[0], 0, ARDRONE_IPADDRESS_SIZE);
787 
788  // TODO(mani-monaj): Check if IP is valid
789  if (drone_ip_address)
790  {
791  printf("===================+> %s\n", drone_ip_address);
792  strncpy(&wifi_ardrone_ip[0], drone_ip_address, ARDRONE_IPADDRESS_SIZE - 1);
793  }
794  else
795  {
796  printf("===================+> %s\n", config->server);
797  strncpy(&wifi_ardrone_ip[0], config->server, ARDRONE_IPADDRESS_SIZE - 1);
798  }
799  }
800 
801  while (-1 == getDroneVersion(".", wifi_ardrone_ip, &ardroneVersion))
802  {
803  printf("Getting AR.Drone version ...\n");
804  vp_os_delay(250);
805  }
806 
807  // Setup communication channels
808  res = ardrone_tool_setup_com(NULL);
809  if (FAILED(res))
810  {
811  PRINT("Wifi initialization failed. It means either:\n");
812  PRINT("\t* you're not root (it's mandatory because you can set up wifi connection only as root)\n");
813  PRINT("\t* wifi device is not present (on your pc or on your card)\n");
814  PRINT("\t* you set the wrong name for wifi interface (for example rausb0 instead of wlan0) \n");
815  PRINT("\t* ap is not up (reboot card or remove wifi usb dongle)\n");
816  PRINT("\t* wifi device has no antenna\n");
817  }
818  else
819  {
820  // setup the application and user profiles for the driver
821  const char* appname = reinterpret_cast<const char*>(DRIVER_APPNAME);
822  const char* usrname = reinterpret_cast<const char*>(DRIVER_USERNAME);
823  ardrone_gen_appid(appname, "2.0", app_id, app_name, APPLI_NAME_SIZE);
824  ardrone_gen_usrid(usrname, usr_id, usr_name, USER_NAME_SIZE);
825 
826  // and finally initialize everything!
827  // this will then call our sdk, which then starts the ::run() method of this file as an ardrone client thread
828 
829  res = ardrone_tool_init(wifi_ardrone_ip,
830  strlen(wifi_ardrone_ip),
831  NULL,
832  app_name,
833  usr_name,
834  NULL,
835  NULL,
836  MAX_FLIGHT_STORING_SIZE,
837  NULL);
838 
839  while (SUCCEED(res) && ardrone_tool_exit() == FALSE)
840  {
841  res = ardrone_tool_update();
842  }
843  res = ardrone_tool_shutdown();
844  }
845  return SUCCEED(res) ? 0 : -1;
846 }
static double CalcAverage(const std::vector< double > &vec)
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
ros::Publisher mag_pub
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
bool SetCamChannelCallback(ardrone_autonomy::CamSelect::Request &request, ardrone_autonomy::CamSelect::Response &response)
ros::Subscriber takeoff_sub
ros::Subscriber land_sub
bool_t ardrone_tool_exit()
std::string drone_frame_id
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
camera_info_manager::CameraInfoManager * cinfo_hori
camera_info_manager::CameraInfoManager * cinfo_vert
#define ROS_WARN_THROTTLE(rate,...)
vp_os_mutex_t video_lock
Definition: ardrone_sdk.cpp:34
ros::Publisher navdata_pub
sensor_msgs::CameraInfo getCameraInfo(void)
int32_t current_navdata_id
Definition: ardrone_sdk.cpp:37
int cam_state
void publish(const boost::shared_ptr< M > &message) const
tf::StampedTransform tf_base_front
ros::Time shared_video_receive_time
Definition: video.cpp:32
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber reset_sub
void CmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
int32_t last_navdata_id
int size() const
uint32_t getNumSubscribers() const
#define D1_MODE3_PIP_HEIGHT
Definition: video.h:53
int32_t copy_current_navdata_id
vp_os_mutex_t navdata_lock
Definition: ardrone_sdk.cpp:33
char buffer[MULTICONFIG_ID_SIZE+1]
tf::TransformBroadcaster tf_broad
image_transport::CameraPublisher vert_pub
bool SetLedAnimationCallback(ardrone_autonomy::LedAnim::Request &request, ardrone_autonomy::LedAnim::Response &response)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void PublishOdometry(const navdata_unpacked_t &navdata_raw, const ros::Time &navdata_receive_time)
image_transport::CameraPublisher hori_pub
video_decoder_config_t vec
int32_t looprate
Definition: ardrone_sdk.cpp:41
int main(int argc, char **argv)
bool ToggleCamCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const navdata_unpacked_t * shared_raw_navdata_ptr
Definition: ardrone_sdk.cpp:30
Type const & getType() const
#define ROS_WARN(...)
image_transport::CameraPublisher image_pub
#define D1_MODE3_PIP_WIDTH
Definition: video.h:52
int32_t copy_current_frame_id
ardrone_autonomy::Navdata legacynavdata_msg
#define D1_STREAM_HEIGHT
Definition: video.h:41
void LandCallback(const std_msgs::Empty &msg)
bool realtime_video
Definition: ardrone_sdk.cpp:43
bool SetRecordCallback(ardrone_autonomy::RecordEnable::Request &request, ardrone_autonomy::RecordEnable::Response &response)
std::string resolve(const std::string &prefix, const std::string &frame_name)
#define _DEG2RAD
ros::Time last_receive_time
bool FlatTrimCallback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
#define D2_STREAM_WIDTH
Definition: video.h:58
std::string child_frame_id_
ros::Publisher odo_pub
#define D1_STREAM_WIDTH
Definition: video.h:40
std::string drone_frame_base
void ResetCallback(const std_msgs::Empty &msg)
#define DRIVER_USERNAME
#define D2_STREAM_HEIGHT
Definition: video.h:59
tf::StampedTransform tf_base_bottom
int32_t current_frame_id
Definition: video.cpp:31
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
static bool isValid()
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
#define ROS_WARN_ONCE(...)
#define ROS_INFO(...)
tf::StampedTransform tf_odom
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define D1_VERTSTREAM_HEIGHT
Definition: video.h:45
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
bool realtime_navdata
Definition: ardrone_sdk.cpp:42
ros::ServiceServer flat_trim_srv
ros::Publisher imu_pub
ros::ServiceServer set_cam_channel_srv
ros::ServiceServer toggle_cam_srv
void sendTransform(const StampedTransform &transform)
ros::ServiceServer set_flight_anim_srv
static bool ReadCovParams(const std::string &param_name, boost::array< double, 9 > &cov_array)
bool SetFlightAnimationCallback(ardrone_autonomy::FlightAnim::Request &request, ardrone_autonomy::FlightAnim::Response &response)
std::string tf_prefix
#define ROS_DEBUG_STREAM(args)
printf("Deleting Profile %s\n", buffer)
int SUCCEED
ros::Time shared_navdata_receive_time
Definition: ardrone_sdk.cpp:31
bool sleep()
#define D1_MODE2_PIP_HEIGHT
Definition: video.h:49
int32_t should_exit
Definition: ardrone_sdk.cpp:45
int32_t last_frame_id
void TakeoffCallback(const std_msgs::Empty &msg)
ros::ServiceServer set_record_srv
uint32_t getNumSubscribers() const
std::string drone_frame_imu
ros::ServiceServer set_led_animation_srv
#define D1_MODE2_PIP_WIDTH
Definition: video.h:48
void ControlCHandler(int signal)
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
std::string drone_frame_front_cam
double odometry[2]
static Time now()
ROSCPP_DECL void shutdown()
ros::NodeHandle private_nh
bool ok() const
bool hasParam(const std::string &key) const
#define D1_VERTSTREAM_WIDTH
Definition: video.h:44
#define ROS_ASSERT(cond)
#define DRIVER_APPNAME
ros::NodeHandle node_handle
ROSCPP_DECL void spinOnce()
geometry_msgs::Vector3Stamped mag_msg
ros::Subscriber cmd_vel_sub
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
void PublishNavdata(const navdata_unpacked_t &navdata_raw, const ros::Time &navdata_receive_time)
std::string frame_id_
sensor_msgs::Imu imu_msg
std::string drone_frame_bottom_cam


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