crazyflie_server.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <ros/callback_queue.h>
3 
4 #include "crazyflie_driver/AddCrazyflie.h"
5 #include "crazyflie_driver/GoTo.h"
6 #include "crazyflie_driver/Land.h"
7 #include "crazyflie_driver/NotifySetpointsStop.h"
8 #include "crazyflie_driver/RemoveCrazyflie.h"
9 #include "crazyflie_driver/SetGroupMask.h"
10 #include "crazyflie_driver/StartTrajectory.h"
11 #include "crazyflie_driver/Stop.h"
12 #include "crazyflie_driver/Takeoff.h"
13 #include "crazyflie_driver/UpdateParams.h"
14 #include "crazyflie_driver/UploadTrajectory.h"
15 #include "crazyflie_driver/sendPacket.h"
16 
17 #include "crazyflie_driver/LogBlock.h"
18 #include "crazyflie_driver/GenericLogData.h"
19 #include "crazyflie_driver/FullState.h"
20 #include "crazyflie_driver/Hover.h"
21 #include "crazyflie_driver/Stop.h"
22 #include "crazyflie_driver/Position.h"
23 #include "crazyflie_driver/VelocityWorld.h"
24 #include "crazyflie_driver/crtpPacket.h"
26 #include "crazyflie_cpp/crtp.h"
27 #include "std_srvs/Empty.h"
28 #include <std_msgs/Empty.h>
29 #include "geometry_msgs/Twist.h"
30 #include "geometry_msgs/PointStamped.h"
31 #include "geometry_msgs/PoseStamped.h"
32 #include "sensor_msgs/Imu.h"
33 #include "sensor_msgs/Temperature.h"
34 #include "sensor_msgs/MagneticField.h"
35 #include "std_msgs/Float32.h"
36 
37 //#include <regex>
38 #include <thread>
39 #include <mutex>
40 
41 #include <string>
42 #include <map>
43 
45 
46 constexpr double pi() { return 3.141592653589793238462643383279502884; }
47 
48 double degToRad(double deg) {
49  return deg / 180.0 * pi();
50 }
51 
52 double radToDeg(double rad) {
53  return rad * 180.0 / pi();
54 }
55 
56 class ROSLogger : public Logger
57 {
58 public:
60  : Logger()
61  {
62  }
63 
64  virtual ~ROSLogger() {}
65 
66  virtual void info(const std::string& msg)
67  {
68  ROS_INFO("%s", msg.c_str());
69  }
70 
71  virtual void warning(const std::string& msg)
72  {
73  ROS_WARN("%s", msg.c_str());
74  }
75 
76  virtual void error(const std::string& msg)
77  {
78  ROS_ERROR("%s", msg.c_str());
79  }
80 };
81 
83 
85 {
86 public:
88  const std::string& link_uri,
89  const std::string& tf_prefix,
90  float roll_trim,
91  float pitch_trim,
92  bool enable_logging,
93  bool enable_parameters,
94  std::vector<crazyflie_driver::LogBlock>& log_blocks,
95  bool use_ros_time,
96  bool enable_logging_imu,
97  bool enable_logging_temperature,
98  bool enable_logging_magnetic_field,
99  bool enable_logging_pressure,
100  bool enable_logging_battery,
101  bool enable_logging_pose,
102  bool enable_logging_packets)
103  : m_tf_prefix(tf_prefix)
104  , m_cf(
105  link_uri,
106  rosLogger,
107  std::bind(&CrazyflieROS::onConsole, this, std::placeholders::_1))
108  , m_isEmergency(false)
109  , m_roll_trim(roll_trim)
110  , m_pitch_trim(pitch_trim)
111  , m_enableLogging(enable_logging)
112  , m_enableParameters(enable_parameters)
113  , m_logBlocks(log_blocks)
114  , m_use_ros_time(use_ros_time)
115  , m_enable_logging_imu(enable_logging_imu)
116  , m_enable_logging_temperature(enable_logging_temperature)
117  , m_enable_logging_magnetic_field(enable_logging_magnetic_field)
118  , m_enable_logging_pressure(enable_logging_pressure)
119  , m_enable_logging_battery(enable_logging_battery)
120  , m_enable_logging_pose(enable_logging_pose)
121  , m_enable_logging_packets(enable_logging_packets)
122  , m_serviceEmergency()
123  , m_serviceUpdateParams()
124  , m_serviceSetGroupMask()
125  , m_serviceTakeoff()
126  , m_serviceLand()
127  , m_serviceStop()
128  , m_serviceGoTo()
129  , m_serviceUploadTrajectory()
130  , m_serviceStartTrajectory()
131  , m_serviceNotifySetpointsStop()
132  , m_subscribeCmdVel()
133  , m_subscribeCmdFullState()
134  , m_subscribeCmdVelocityWorld()
135  , m_subscribeCmdHover()
136  , m_subscribeCmdStop()
137  , m_subscribeCmdPosition()
138  , m_subscribeExternalPosition()
139  , m_pubImu()
140  , m_pubTemp()
141  , m_pubMag()
142  , m_pubPressure()
143  , m_pubBattery()
144  , m_pubRssi()
145  , m_sentSetpoint(false)
146  , m_sentExternalPosition(false)
147  {
148  m_thread = std::thread(&CrazyflieROS::run, this);
149  }
150 
151  void stop()
152  {
153  ROS_INFO_NAMED(m_tf_prefix, "Disconnecting ...");
154  m_isEmergency = true;
155  m_thread.join();
156  }
157 
164  bool sendPacket (
165  crazyflie_driver::sendPacket::Request &req,
166  crazyflie_driver::sendPacket::Response &res)
167  {
169  crtpPacket_t packet;
170  packet.size = req.packet.size;
171  packet.header = req.packet.header;
172  for (int i = 0; i < CRTP_MAX_DATA_SIZE; i++) {
173  packet.data[i] = req.packet.data[i];
174  }
175  m_cf.queueOutgoingPacket(packet);
176  return true;
177  }
178 
179 private:
180  struct logImu {
181  float acc_x;
182  float acc_y;
183  float acc_z;
184  float gyro_x;
185  float gyro_y;
186  float gyro_z;
187  } __attribute__((packed));
188 
189  struct log2 {
190  float mag_x;
191  float mag_y;
192  float mag_z;
193  float baro_temp;
195  float pm_vbat;
196  } __attribute__((packed));
197 
198  struct logPose {
199  float x;
200  float y;
201  float z;
202  int32_t quatCompressed;
203  } __attribute__((packed));
204 
205 private:
206  bool emergency(
207  std_srvs::Empty::Request& req,
208  std_srvs::Empty::Response& res)
209  {
210  ROS_FATAL_NAMED(m_tf_prefix, "Emergency requested!");
211  m_isEmergency = true;
212  m_cf.emergencyStop();
213 
214  return true;
215  }
216 
217  template<class T, class U>
218  void updateParam(uint16_t id, const std::string& ros_param) {
219  U value;
220  ros::param::get(ros_param, value);
221  m_cf.setParam<T>(id, (T)value);
222  }
223 
225  const crazyflie_driver::Hover::ConstPtr& msg)
226  {
227  //ROS_INFO("got a hover setpoint");
228  if (!m_isEmergency) {
229  float vx = msg->vx;
230  float vy = msg->vy;
231  float yawRate = msg->yawrate;
232  float zDistance = msg->zDistance;
233 
234  m_cf.sendHoverSetpoint(vx, vy, yawRate, zDistance);
235  m_sentSetpoint = true;
236  //ROS_INFO("set a hover setpoint");
237  }
238  }
239 
240 void cmdStop(
241  const std_msgs::Empty::ConstPtr& msg)
242  {
243  //ROS_INFO("got a stop setpoint");
244  if (!m_isEmergency) {
245  m_cf.sendStop();
246  m_sentSetpoint = true;
247  //ROS_INFO("set a stop setpoint");
248  }
249  }
250 
252  const crazyflie_driver::Position::ConstPtr& msg)
253  {
254  if(!m_isEmergency) {
255  float x = msg->x;
256  float y = msg->y;
257  float z = msg->z;
258  float yaw = msg->yaw;
259 
260  m_cf.sendPositionSetpoint(x, y, z, yaw);
261  m_sentSetpoint = true;
262  }
263  }
264 
266  crazyflie_driver::UpdateParams::Request& req,
267  crazyflie_driver::UpdateParams::Response& res)
268  {
269  ROS_INFO_NAMED(m_tf_prefix, "Update parameters");
270  for (auto&& p : req.params) {
271  std::string ros_param = "/" + m_tf_prefix + "/" + p;
272  size_t pos = p.find("/");
273  std::string group(p.begin(), p.begin() + pos);
274  std::string name(p.begin() + pos + 1, p.end());
275 
276  auto entry = m_cf.getParamTocEntry(group, name);
277  if (entry)
278  {
279  switch (entry->type) {
281  updateParam<uint8_t, int>(entry->id, ros_param);
282  break;
284  updateParam<int8_t, int>(entry->id, ros_param);
285  break;
287  updateParam<uint16_t, int>(entry->id, ros_param);
288  break;
290  updateParam<int16_t, int>(entry->id, ros_param);
291  break;
293  updateParam<uint32_t, int>(entry->id, ros_param);
294  break;
296  updateParam<int32_t, int>(entry->id, ros_param);
297  break;
299  updateParam<float, float>(entry->id, ros_param);
300  break;
301  }
302  }
303  else {
304  ROS_ERROR_NAMED(m_tf_prefix, "Could not find param %s/%s", group.c_str(), name.c_str());
305  }
306  }
307  return true;
308  }
309 
311  const geometry_msgs::Twist::ConstPtr& msg)
312  {
313  if (!m_isEmergency) {
314  float roll = msg->linear.y + m_roll_trim;
315  float pitch = - (msg->linear.x + m_pitch_trim);
316  float yawrate = msg->angular.z;
317  uint16_t thrust = std::min<uint16_t>(std::max<float>(msg->linear.z, 0.0), 60000);
318 
319  m_cf.sendSetpoint(roll, pitch, yawrate, thrust);
320  m_sentSetpoint = true;
321  }
322  }
323 
325  const crazyflie_driver::FullState::ConstPtr& msg)
326  {
327  //ROS_INFO("got a full state setpoint");
328  if (!m_isEmergency) {
329  float x = msg->pose.position.x;
330  float y = msg->pose.position.y;
331  float z = msg->pose.position.z;
332  float vx = msg->twist.linear.x;
333  float vy = msg->twist.linear.y;
334  float vz = msg->twist.linear.z;
335  float ax = msg->acc.x;
336  float ay = msg->acc.y;
337  float az = msg->acc.z;
338 
339  float qx = msg->pose.orientation.x;
340  float qy = msg->pose.orientation.y;
341  float qz = msg->pose.orientation.z;
342  float qw = msg->pose.orientation.w;
343  float rollRate = msg->twist.angular.x;
344  float pitchRate = msg->twist.angular.y;
345  float yawRate = msg->twist.angular.z;
346 
347  m_cf.sendFullStateSetpoint(
348  x, y, z,
349  vx, vy, vz,
350  ax, ay, az,
351  qx, qy, qz, qw,
352  rollRate, pitchRate, yawRate);
353  m_sentSetpoint = true;
354  //ROS_INFO("set a full state setpoint");
355  }
356  }
357 
359  const crazyflie_driver::VelocityWorld::ConstPtr& msg)
360  {
361  //ROS_INFO("got a velocity world setpoint");
362  if (!m_isEmergency) {
363  float x = msg->vel.x;
364  float y = msg->vel.y;
365  float z = msg->vel.z;
366  float yawRate = msg->yawRate;
367 
368  m_cf.sendVelocityWorldSetpoint(
369  x, y, z, yawRate);
370  m_sentSetpoint = true;
371  //ROS_INFO("set a velocity world setpoint");
372  }
373  }
374 
376  const geometry_msgs::PointStamped::ConstPtr& msg)
377  {
378  m_cf.sendExternalPositionUpdate(msg->point.x, msg->point.y, msg->point.z);
379  m_sentExternalPosition = true;
380  }
381 
383  const geometry_msgs::PoseStamped::ConstPtr& msg)
384  {
385  m_cf.sendExternalPoseUpdate(
386  msg->pose.position.x, msg->pose.position.y, msg->pose.position.z,
387  msg->pose.orientation.x, msg->pose.orientation.y, msg->pose.orientation.z, msg->pose.orientation.w);
388  m_sentExternalPosition = true;
389  }
390 
391  void run()
392  {
393  ros::NodeHandle n;
394  n.setCallbackQueue(&m_callback_queue);
395 
396  m_subscribeCmdVel = n.subscribe(m_tf_prefix + "/cmd_vel", 1, &CrazyflieROS::cmdVelChanged, this);
397  m_subscribeCmdFullState = n.subscribe(m_tf_prefix + "/cmd_full_state", 1, &CrazyflieROS::cmdFullStateSetpoint, this);
398  m_subscribeCmdVelocityWorld = n.subscribe(m_tf_prefix+"/cmd_velocity_world", 1, &CrazyflieROS::cmdVelocityWorldSetpoint, this);
399  m_subscribeExternalPosition = n.subscribe(m_tf_prefix + "/external_position", 1, &CrazyflieROS::positionMeasurementChanged, this);
400  m_subscribeExternalPose = n.subscribe(m_tf_prefix + "/external_pose", 1, &CrazyflieROS::poseMeasurementChanged, this);
401  m_serviceEmergency = n.advertiseService(m_tf_prefix + "/emergency", &CrazyflieROS::emergency, this);
402  m_subscribeCmdHover = n.subscribe(m_tf_prefix + "/cmd_hover", 1, &CrazyflieROS::cmdHoverSetpoint, this);
403  m_subscribeCmdStop = n.subscribe(m_tf_prefix + "/cmd_stop", 1, &CrazyflieROS::cmdStop, this);
404  m_subscribeCmdPosition = n.subscribe(m_tf_prefix + "/cmd_position", 1, &CrazyflieROS::cmdPositionSetpoint, this);
405 
406 
407  m_serviceSetGroupMask = n.advertiseService(m_tf_prefix + "/set_group_mask", &CrazyflieROS::setGroupMask, this);
408  m_serviceTakeoff = n.advertiseService(m_tf_prefix + "/takeoff", &CrazyflieROS::takeoff, this);
409  m_serviceLand = n.advertiseService(m_tf_prefix + "/land", &CrazyflieROS::land, this);
410  m_serviceStop = n.advertiseService(m_tf_prefix + "/stop", &CrazyflieROS::stop, this);
411  m_serviceGoTo = n.advertiseService(m_tf_prefix + "/go_to", &CrazyflieROS::goTo, this);
412  m_serviceUploadTrajectory = n.advertiseService(m_tf_prefix + "/upload_trajectory", &CrazyflieROS::uploadTrajectory, this);
413  m_serviceStartTrajectory = n.advertiseService(m_tf_prefix + "/start_trajectory", &CrazyflieROS::startTrajectory, this);
414  m_serviceNotifySetpointsStop = n.advertiseService(m_tf_prefix + "/notify_setpoints_stop", &CrazyflieROS::notifySetpointsStop, this);
415 
416  if (m_enable_logging_imu) {
417  m_pubImu = n.advertise<sensor_msgs::Imu>(m_tf_prefix + "/imu", 10);
418  }
419  if (m_enable_logging_temperature) {
420  m_pubTemp = n.advertise<sensor_msgs::Temperature>(m_tf_prefix + "/temperature", 10);
421  }
422  if (m_enable_logging_magnetic_field) {
423  m_pubMag = n.advertise<sensor_msgs::MagneticField>(m_tf_prefix + "/magnetic_field", 10);
424  }
425  if (m_enable_logging_pressure) {
426  m_pubPressure = n.advertise<std_msgs::Float32>(m_tf_prefix + "/pressure", 10);
427  }
428  if (m_enable_logging_battery) {
429  m_pubBattery = n.advertise<std_msgs::Float32>(m_tf_prefix + "/battery", 10);
430  }
431  if (m_enable_logging_pose) {
432  m_pubPose = n.advertise<geometry_msgs::PoseStamped>(m_tf_prefix + "/pose", 10);
433  }
434  if (m_enable_logging_packets) {
435  m_pubPackets = n.advertise<crazyflie_driver::crtpPacket>(m_tf_prefix + "/packets", 10);
436  std::function<void(const ITransport::Ack&)> cb_genericPacket = std::bind(&CrazyflieROS::onGenericPacket, this, std::placeholders::_1);
437  m_cf.setGenericPacketCallback(cb_genericPacket);
438  }
439  m_pubRssi = n.advertise<std_msgs::Float32>(m_tf_prefix + "/rssi", 10);
440 
441  for (auto& logBlock : m_logBlocks)
442  {
443  m_pubLogDataGeneric.push_back(n.advertise<crazyflie_driver::GenericLogData>(m_tf_prefix + "/" + logBlock.topic_name, 10));
444  }
445 
446  m_sendPacketServer = n.advertiseService(m_tf_prefix + "/send_packet" , &CrazyflieROS::sendPacket, this);
447 
448  // m_cf.reboot();
449 
450  auto start = std::chrono::system_clock::now();
451 
452  m_cf.logReset();
453 
454  std::function<void(float)> cb_lq = std::bind(&CrazyflieROS::onLinkQuality, this, std::placeholders::_1);
455  m_cf.setLinkQualityCallback(cb_lq);
456 
457  if (m_enableParameters)
458  {
459  ROS_INFO_NAMED(m_tf_prefix, "Requesting parameters...");
460  m_cf.requestParamToc();
461  for (auto iter = m_cf.paramsBegin(); iter != m_cf.paramsEnd(); ++iter) {
462  auto entry = *iter;
463  std::string paramName = "/" + m_tf_prefix + "/" + entry.group + "/" + entry.name;
464  switch (entry.type) {
466  ros::param::set(paramName, m_cf.getParam<uint8_t>(entry.id));
467  break;
469  ros::param::set(paramName, m_cf.getParam<int8_t>(entry.id));
470  break;
472  ros::param::set(paramName, m_cf.getParam<uint16_t>(entry.id));
473  break;
475  ros::param::set(paramName, m_cf.getParam<int16_t>(entry.id));
476  break;
478  ros::param::set(paramName, (int)m_cf.getParam<uint32_t>(entry.id));
479  break;
481  ros::param::set(paramName, m_cf.getParam<int32_t>(entry.id));
482  break;
484  ros::param::set(paramName, m_cf.getParam<float>(entry.id));
485  break;
486  }
487  }
488  m_serviceUpdateParams = n.advertiseService(m_tf_prefix + "/update_params", &CrazyflieROS::updateParams, this);
489  }
490 
491  std::unique_ptr<LogBlock<logImu> > logBlockImu;
492  std::unique_ptr<LogBlock<log2> > logBlock2;
493  std::unique_ptr<LogBlock<logPose> > logBlockPose;
494  std::vector<std::unique_ptr<LogBlockGeneric> > logBlocksGeneric(m_logBlocks.size());
495  if (m_enableLogging) {
496 
497  std::function<void(const crtpPlatformRSSIAck*)> cb_ack = std::bind(&CrazyflieROS::onEmptyAck, this, std::placeholders::_1);
498  m_cf.setEmptyAckCallback(cb_ack);
499 
500  ROS_INFO_NAMED(m_tf_prefix, "Requesting Logging variables...");
501  m_cf.requestLogToc();
502 
503  if (m_enable_logging_imu) {
504  std::function<void(uint32_t, logImu*)> cb = std::bind(&CrazyflieROS::onImuData, this, std::placeholders::_1, std::placeholders::_2);
505 
506  logBlockImu.reset(new LogBlock<logImu>(
507  &m_cf,{
508  {"acc", "x"},
509  {"acc", "y"},
510  {"acc", "z"},
511  {"gyro", "x"},
512  {"gyro", "y"},
513  {"gyro", "z"},
514  }, cb));
515  logBlockImu->start(1); // 10ms
516  }
517 
518  if ( m_enable_logging_temperature
519  || m_enable_logging_magnetic_field
520  || m_enable_logging_pressure
521  || m_enable_logging_battery)
522  {
523  std::function<void(uint32_t, log2*)> cb2 = std::bind(&CrazyflieROS::onLog2Data, this, std::placeholders::_1, std::placeholders::_2);
524 
525  logBlock2.reset(new LogBlock<log2>(
526  &m_cf,{
527  {"mag", "x"},
528  {"mag", "y"},
529  {"mag", "z"},
530  {"baro", "temp"},
531  {"baro", "pressure"},
532  {"pm", "vbat"},
533  }, cb2));
534  logBlock2->start(10); // 100ms
535  }
536 
537  if (m_enable_logging_pose) {
538  std::function<void(uint32_t, logPose*)> cb = std::bind(&CrazyflieROS::onPoseData, this, std::placeholders::_1, std::placeholders::_2);
539 
540  logBlockPose.reset(new LogBlock<logPose>(
541  &m_cf,{
542  {"stateEstimate", "x"},
543  {"stateEstimate", "y"},
544  {"stateEstimate", "z"},
545  {"stateEstimateZ", "quat"}
546  }, cb));
547  logBlockPose->start(1); // 10ms
548  }
549 
550  // custom log blocks
551  size_t i = 0;
552  for (auto& logBlock : m_logBlocks)
553  {
554  std::function<void(uint32_t, std::vector<double>*, void* userData)> cb =
555  std::bind(
557  this,
558  std::placeholders::_1,
559  std::placeholders::_2,
560  std::placeholders::_3);
561 
562  logBlocksGeneric[i].reset(new LogBlockGeneric(
563  &m_cf,
564  logBlock.variables,
565  (void*)&m_pubLogDataGeneric[i],
566  cb));
567  logBlocksGeneric[i]->start(logBlock.frequency / 10);
568  ++i;
569  }
570 
571 
572  }
573 
574  ROS_INFO_NAMED(m_tf_prefix, "Requesting memories...");
575  m_cf.requestMemoryToc();
576 
577  ROS_INFO_NAMED(m_tf_prefix, "Ready...");
578  auto end = std::chrono::system_clock::now();
579  std::chrono::duration<double> elapsedSeconds = end-start;
580  ROS_INFO_NAMED(m_tf_prefix, "Elapsed: %f s", elapsedSeconds.count());
581 
582  // Send 0 thrust initially for thrust-lock
583  for (int i = 0; i < 100; ++i) {
584  m_cf.sendSetpoint(0, 0, 0, 0);
585  }
586 
587  while(!m_isEmergency) {
588  // make sure we ping often enough to stream data out
589  if (m_enableLogging && !m_sentSetpoint && !m_sentExternalPosition) {
590  m_cf.transmitPackets();
591  m_cf.sendPing();
592  }
593  m_sentSetpoint = false;
594  m_sentExternalPosition = false;
595 
596  // Execute any ROS related functions now
597  m_callback_queue.callAvailable(ros::WallDuration(0.0));
598  std::this_thread::sleep_for(std::chrono::milliseconds(1));
599  }
600 
601  // Make sure we turn the engines off
602  for (int i = 0; i < 100; ++i) {
603  m_cf.sendSetpoint(0, 0, 0, 0);
604  }
605 
606  }
607 
608  void onImuData(uint32_t time_in_ms, logImu* data) {
609  if (m_enable_logging_imu) {
610  sensor_msgs::Imu msg;
611  if (m_use_ros_time) {
612  msg.header.stamp = ros::Time::now();
613  } else {
614  msg.header.stamp = ros::Time(time_in_ms / 1000.0);
615  }
616  msg.header.frame_id = m_tf_prefix + "/base_link";
617  msg.orientation_covariance[0] = -1;
618 
619  // measured in deg/s; need to convert to rad/s
620  msg.angular_velocity.x = degToRad(data->gyro_x);
621  msg.angular_velocity.y = degToRad(data->gyro_y);
622  msg.angular_velocity.z = degToRad(data->gyro_z);
623 
624  // measured in mG; need to convert to m/s^2
625  msg.linear_acceleration.x = data->acc_x * 9.81;
626  msg.linear_acceleration.y = data->acc_y * 9.81;
627  msg.linear_acceleration.z = data->acc_z * 9.81;
628 
629  m_pubImu.publish(msg);
630  }
631  }
632 
633  void onLog2Data(uint32_t time_in_ms, log2* data) {
634 
635  if (m_enable_logging_temperature) {
636  sensor_msgs::Temperature msg;
637  if (m_use_ros_time) {
638  msg.header.stamp = ros::Time::now();
639  } else {
640  msg.header.stamp = ros::Time(time_in_ms / 1000.0);
641  }
642  msg.header.frame_id = m_tf_prefix + "/base_link";
643  // measured in degC
644  msg.temperature = data->baro_temp;
645  m_pubTemp.publish(msg);
646  }
647 
648  if (m_enable_logging_magnetic_field) {
649  sensor_msgs::MagneticField msg;
650  if (m_use_ros_time) {
651  msg.header.stamp = ros::Time::now();
652  } else {
653  msg.header.stamp = ros::Time(time_in_ms / 1000.0);
654  }
655  msg.header.frame_id = m_tf_prefix + "/base_link";
656 
657  // measured in Tesla
658  msg.magnetic_field.x = data->mag_x;
659  msg.magnetic_field.y = data->mag_y;
660  msg.magnetic_field.z = data->mag_z;
661  m_pubMag.publish(msg);
662  }
663 
664  if (m_enable_logging_pressure) {
665  std_msgs::Float32 msg;
666  // hPa (=mbar)
667  msg.data = data->baro_pressure;
668  m_pubPressure.publish(msg);
669  }
670 
671  if (m_enable_logging_battery) {
672  std_msgs::Float32 msg;
673  // V
674  msg.data = data->pm_vbat;
675  m_pubBattery.publish(msg);
676  }
677  }
678 
679  void onPoseData(uint32_t time_in_ms, logPose* data) {
680  if (m_enable_logging_pose) {
681  geometry_msgs::PoseStamped msg;
682  if (m_use_ros_time) {
683  msg.header.stamp = ros::Time::now();
684  } else {
685  msg.header.stamp = ros::Time(time_in_ms / 1000.0);
686  }
687  msg.header.frame_id = m_tf_prefix + "/base_link";
688 
689  msg.pose.position.x = data->x;
690  msg.pose.position.y = data->y;
691  msg.pose.position.z = data->z;
692 
693  float q[4];
694  quatdecompress(data->quatCompressed, q);
695  msg.pose.orientation.x = q[0];
696  msg.pose.orientation.y = q[1];
697  msg.pose.orientation.z = q[2];
698  msg.pose.orientation.w = q[3];
699 
700  m_pubPose.publish(msg);
701  }
702  }
703 
704  void onLogCustom(uint32_t time_in_ms, std::vector<double>* values, void* userData) {
705 
706  ros::Publisher* pub = reinterpret_cast<ros::Publisher*>(userData);
707 
708  crazyflie_driver::GenericLogData msg;
709  if (m_use_ros_time) {
710  msg.header.stamp = ros::Time::now();
711  } else {
712  msg.header.stamp = ros::Time(time_in_ms / 1000.0);
713  }
714  msg.header.frame_id = m_tf_prefix + "/base_link";
715  msg.values = *values;
716 
717  pub->publish(msg);
718  }
719 
720  void onEmptyAck(const crtpPlatformRSSIAck* data) {
721  std_msgs::Float32 msg;
722  // dB
723  msg.data = data->rssi;
724  m_pubRssi.publish(msg);
725  }
726 
727  void onLinkQuality(float linkQuality) {
728  if (linkQuality < 0.7) {
729  ROS_WARN_NAMED(m_tf_prefix, "Link Quality low (%f)", linkQuality);
730  }
731  }
732 
733  void onConsole(const char* msg) {
734  static std::string messageBuffer;
735  messageBuffer += msg;
736  size_t pos = messageBuffer.find('\n');
737  if (pos != std::string::npos) {
738  messageBuffer[pos] = 0;
739  ROS_INFO_NAMED(m_tf_prefix, "CF Console: %s", messageBuffer.c_str());
740  messageBuffer.erase(0, pos+1);
741  }
742  }
743 
744  void onGenericPacket(const ITransport::Ack& ack) {
745  crazyflie_driver::crtpPacket packet;
746  packet.size = ack.size;
747  packet.header = ack.data[0];
748  memcpy(&packet.data[0], &ack.data[1], ack.size);
749  m_pubPackets.publish(packet);
750  }
751 
753  crazyflie_driver::SetGroupMask::Request& req,
754  crazyflie_driver::SetGroupMask::Response& res)
755  {
756  ROS_INFO_NAMED(m_tf_prefix, "SetGroupMask requested");
757  m_cf.setGroupMask(req.groupMask);
758  return true;
759  }
760 
761  bool takeoff(
762  crazyflie_driver::Takeoff::Request& req,
763  crazyflie_driver::Takeoff::Response& res)
764  {
765  ROS_INFO_NAMED(m_tf_prefix, "Takeoff requested");
766  m_cf.takeoff(req.height, req.duration.toSec(), req.groupMask);
767  return true;
768  }
769 
770  bool land(
771  crazyflie_driver::Land::Request& req,
772  crazyflie_driver::Land::Response& res)
773  {
774  ROS_INFO_NAMED(m_tf_prefix, "Land requested");
775  m_cf.land(req.height, req.duration.toSec(), req.groupMask);
776  return true;
777  }
778 
779  bool stop(
780  crazyflie_driver::Stop::Request& req,
781  crazyflie_driver::Stop::Response& res)
782  {
783  ROS_INFO_NAMED(m_tf_prefix, "Stop requested");
784  m_cf.stop(req.groupMask);
785  return true;
786  }
787 
788  bool goTo(
789  crazyflie_driver::GoTo::Request& req,
790  crazyflie_driver::GoTo::Response& res)
791  {
792  ROS_INFO_NAMED(m_tf_prefix, "GoTo requested");
793  m_cf.goTo(req.goal.x, req.goal.y, req.goal.z, req.yaw, req.duration.toSec(), req.relative, req.groupMask);
794  return true;
795  }
796 
798  crazyflie_driver::UploadTrajectory::Request& req,
799  crazyflie_driver::UploadTrajectory::Response& res)
800  {
801  ROS_INFO_NAMED(m_tf_prefix, "UploadTrajectory requested");
802 
803  std::vector<Crazyflie::poly4d> pieces(req.pieces.size());
804  for (size_t i = 0; i < pieces.size(); ++i) {
805  if ( req.pieces[i].poly_x.size() != 8
806  || req.pieces[i].poly_y.size() != 8
807  || req.pieces[i].poly_z.size() != 8
808  || req.pieces[i].poly_yaw.size() != 8) {
809  ROS_FATAL_NAMED(m_tf_prefix, "Wrong number of pieces!");
810  return false;
811  }
812  pieces[i].duration = req.pieces[i].duration.toSec();
813  for (size_t j = 0; j < 8; ++j) {
814  pieces[i].p[0][j] = req.pieces[i].poly_x[j];
815  pieces[i].p[1][j] = req.pieces[i].poly_y[j];
816  pieces[i].p[2][j] = req.pieces[i].poly_z[j];
817  pieces[i].p[3][j] = req.pieces[i].poly_yaw[j];
818  }
819  }
820  m_cf.uploadTrajectory(req.trajectoryId, req.pieceOffset, pieces);
821 
822  ROS_INFO_NAMED(m_tf_prefix, "Upload completed!");
823  return true;
824  }
825 
827  crazyflie_driver::StartTrajectory::Request& req,
828  crazyflie_driver::StartTrajectory::Response& res)
829  {
830  ROS_INFO_NAMED(m_tf_prefix, "StartTrajectory requested");
831  m_cf.startTrajectory(req.trajectoryId, req.timescale, req.reversed, req.relative, req.groupMask);
832  return true;
833  }
834 
836  crazyflie_driver::NotifySetpointsStop::Request& req,
837  crazyflie_driver::NotifySetpointsStop::Response& res)
838  {
839  ROS_INFO_NAMED(m_tf_prefix, "NotifySetpointsStop requested");
840  m_cf.notifySetpointsStop(req.remainValidMillisecs);
841  return true;
842  }
843 
844 private:
845  std::string m_tf_prefix;
848  float m_roll_trim;
852  std::vector<crazyflie_driver::LogBlock> m_logBlocks;
861 
865 
866  // High-level setpoints
875 
892  std::vector<ros::Publisher> m_pubLogDataGeneric;
893 
894  bool m_sentSetpoint, m_sentExternalPosition;
895 
896  std::thread m_thread;
898 };
899 
901 {
902 public:
904  {
905 
906  }
907 
908  void run()
909  {
910  ros::NodeHandle n;
911  ros::CallbackQueue callback_queue;
912  n.setCallbackQueue(&callback_queue);
913 
914  ros::ServiceServer serviceAdd = n.advertiseService("add_crazyflie", &CrazyflieServer::add_crazyflie, this);
915  ros::ServiceServer serviceRemove = n.advertiseService("remove_crazyflie", &CrazyflieServer::remove_crazyflie, this);
916 
917  // // High-level API
918  // ros::ServiceServer serviceTakeoff = n.advertiseService("takeoff", &CrazyflieServer::takeoff, this);
919  // ros::ServiceServer serviceLand = n.advertiseService("land", &CrazyflieROS::land, this);
920  // ros::ServiceServer serviceStop = n.advertiseService("stop", &CrazyflieROS::stop, this);
921  // ros::ServiceServer serviceGoTo = n.advertiseService("go_to", &CrazyflieROS::goTo, this);
922  // ros::ServiceServer startTrajectory = n.advertiseService("start_trajectory", &CrazyflieROS::startTrajectory, this);
923 
924  while(ros::ok()) {
925  // Execute any ROS related functions now
926  callback_queue.callAvailable(ros::WallDuration(0.0));
927  std::this_thread::sleep_for(std::chrono::milliseconds(1));
928  }
929  }
930 
931 private:
932 
934  crazyflie_driver::AddCrazyflie::Request &req,
935  crazyflie_driver::AddCrazyflie::Response &res)
936  {
937  ROS_INFO("Adding %s as %s with trim(%f, %f). Logging: %d, Parameters: %d, Use ROS time: %d",
938  req.uri.c_str(),
939  req.tf_prefix.c_str(),
940  req.roll_trim,
941  req.pitch_trim,
942  req.enable_parameters,
943  req.enable_logging,
944  req.use_ros_time);
945 
946  // Ignore if the uri is already in use
947  if (m_crazyflies.find(req.uri) != m_crazyflies.end()) {
948  ROS_ERROR("Cannot add %s, already added.", req.uri.c_str());
949  return false;
950  }
951 
953  req.uri,
954  req.tf_prefix,
955  req.roll_trim,
956  req.pitch_trim,
957  req.enable_logging,
958  req.enable_parameters,
959  req.log_blocks,
960  req.use_ros_time,
961  req.enable_logging_imu,
962  req.enable_logging_temperature,
963  req.enable_logging_magnetic_field,
964  req.enable_logging_pressure,
965  req.enable_logging_battery,
966  req.enable_logging_pose,
967  req.enable_logging_packets);
968 
969  m_crazyflies[req.uri] = cf;
970 
971  return true;
972  }
973 
975  crazyflie_driver::RemoveCrazyflie::Request &req,
976  crazyflie_driver::RemoveCrazyflie::Response &res)
977  {
978 
979  if (m_crazyflies.find(req.uri) == m_crazyflies.end()) {
980  ROS_ERROR("Cannot remove %s, not connected.", req.uri.c_str());
981  return false;
982  }
983 
984  ROS_INFO("Removing crazyflie at uri %s.", req.uri.c_str());
985 
986  m_crazyflies[req.uri]->stop();
987  delete m_crazyflies[req.uri];
988  m_crazyflies.erase(req.uri);
989 
990  ROS_INFO("Crazyflie %s removed.", req.uri.c_str());
991 
992  return true;
993  }
994 
995  // bool takeoff(
996  // crazyflie_driver::Takeoff::Request& req,
997  // crazyflie_driver::Takeoff::Response& res)
998  // {
999  // ROS_INFO("Takeoff requested");
1000  // m_cfbc.takeoff(req.height, req.duration.toSec(), req.groupMask);
1001  // return true;
1002  // }
1003 
1004  // bool land(
1005  // crazyflie_driver::Land::Request& req,
1006  // crazyflie_driver::Land::Response& res)
1007  // {
1008  // ROS_INFO("Land requested");
1009  // m_cfbc.land(req.height, req.duration.toSec(), req.groupMask);
1010  // return true;
1011  // }
1012 
1013  // bool stop(
1014  // crazyflie_driver::Stop::Request& req,
1015  // crazyflie_driver::Stop::Response& res)
1016  // {
1017  // ROS_INFO("Stop requested");
1018  // m_cfbc.stop(req.groupMask);
1019  // return true;
1020  // }
1021 
1022  // bool goTo(
1023  // crazyflie_driver::GoTo::Request& req,
1024  // crazyflie_driver::GoTo::Response& res)
1025  // {
1026  // ROS_INFO("GoTo requested");
1027  // // this is always relative
1028  // m_cfbc.goTo(req.goal.x, req.goal.y, req.goal.z, req.yaw, req.duration.toSec(), req.groupMask);
1029  // return true;
1030  // }
1031 
1032  // bool startTrajectory(
1033  // crazyflie_driver::StartTrajectory::Request& req,
1034  // crazyflie_driver::StartTrajectory::Response& res)
1035  // {
1036  // ROS_INFO("StartTrajectory requested");
1037  // // this is always relative
1038  // m_cfbc.startTrajectory(req.index, req.numPieces, req.timescale, req.reversed, req.groupMask);
1039  // return true;
1040  // }
1041 
1042 private:
1043  std::map<std::string, CrazyflieROS*> m_crazyflies;
1044 };
1045 
1046 
1047 
1048 
1049 int main(int argc, char **argv)
1050 {
1051  ros::init(argc, argv, "crazyflie_server");
1052 
1053  CrazyflieServer cfserver;
1054  cfserver.run();
1055 
1056  return 0;
1057 }
bool emergency(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
float qy
bool m_enable_logging_magnetic_field
float y
float yawrate
double degToRad(double deg)
float vy
void quatdecompress(uint32_t comp, float q[4])
ros::Publisher m_pubMag
#define ROS_INFO_NAMED(name,...)
void onGenericPacket(const ITransport::Ack &ack)
ros::ServiceServer m_serviceTakeoff
void cmdVelChanged(const geometry_msgs::Twist::ConstPtr &msg)
float p[4][8]
int16_t vz
void publish(const boost::shared_ptr< M > &message) const
const T value
float vx
void poseMeasurementChanged(const geometry_msgs::PoseStamped::ConstPtr &msg)
#define ROS_WARN_NAMED(name,...)
ros::Publisher m_pubBattery
ros::ServiceServer m_serviceLand
ros::ServiceServer m_serviceNotifySetpointsStop
float zDistance
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool m_enable_logging_temperature
ros::ServiceServer m_serviceEmergency
void cmdHoverSetpoint(const crazyflie_driver::Hover::ConstPtr &msg)
bool updateParams(crazyflie_driver::UpdateParams::Request &req, crazyflie_driver::UpdateParams::Response &res)
uint8_t data[CRTP_MAX_DATA_SIZE]
bool goTo(crazyflie_driver::GoTo::Request &req, crazyflie_driver::GoTo::Response &res)
float qw
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
typedef __attribute__
bool remove_crazyflie(crazyflie_driver::RemoveCrazyflie::Request &req, crazyflie_driver::RemoveCrazyflie::Response &res)
ros::ServiceServer m_sendPacketServer
uint8_t data[32]
void onEmptyAck(const crtpPlatformRSSIAck *data)
ros::Subscriber m_subscribeExternalPosition
void onImuData(uint32_t time_in_ms, logImu *data)
bool stop(crazyflie_driver::Stop::Request &req, crazyflie_driver::Stop::Response &res)
ros::Publisher m_pubTemp
bool notifySetpointsStop(crazyflie_driver::NotifySetpointsStop::Request &req, crazyflie_driver::NotifySetpointsStop::Response &res)
std::vector< crazyflie_driver::LogBlock > m_logBlocks
void onConsole(const char *msg)
ros::Subscriber m_subscribeExternalPose
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer m_serviceSetGroupMask
#define ROS_WARN(...)
bool startTrajectory(crazyflie_driver::StartTrajectory::Request &req, crazyflie_driver::StartTrajectory::Response &res)
void cmdStop(const std_msgs::Empty::ConstPtr &msg)
virtual void error(const std::string &msg)
bool setGroupMask(crazyflie_driver::SetGroupMask::Request &req, crazyflie_driver::SetGroupMask::Response &res)
float x
start
ros::CallbackQueue m_callback_queue
cf
std::vector< ros::Publisher > m_pubLogDataGeneric
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool add_crazyflie(crazyflie_driver::AddCrazyflie::Request &req, crazyflie_driver::AddCrazyflie::Response &res)
virtual ~ROSLogger()
uint8_t group
float yaw
char name[30]
msg
void cmdFullStateSetpoint(const crazyflie_driver::FullState::ConstPtr &msg)
ros::Subscriber m_subscribeCmdPosition
pub
ROSCPP_DECL bool get(const std::string &key, std::string &s)
ros::ServiceServer m_serviceGoTo
void onLinkQuality(float linkQuality)
#define ROS_INFO(...)
ros::ServiceServer m_serviceStartTrajectory
void setCallbackQueue(CallbackQueueInterface *queue)
std::thread m_thread
bool m_enable_logging_pressure
void updateParam(uint16_t id, const std::string &ros_param)
ROSCPP_DECL bool ok()
float yawRate
bool takeoff(crazyflie_driver::Takeoff::Request &req, crazyflie_driver::Takeoff::Response &res)
int16_t ay
virtual void warning(const std::string &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::map< std::string, CrazyflieROS * > m_crazyflies
void onLogCustom(uint32_t time_in_ms, std::vector< double > *values, void *userData)
void onPoseData(uint32_t time_in_ms, logPose *data)
ros::Publisher m_pubImu
uint8_t size
virtual void info(const std::string &msg)
ros::ServiceServer m_serviceUpdateParams
float z
int main(int argc, char **argv)
ros::Subscriber m_subscribeCmdHover
void cmdVelocityWorldSetpoint(const crazyflie_driver::VelocityWorld::ConstPtr &msg)
static ROSLogger rosLogger
int16_t az
constexpr double pi()
ros::ServiceServer m_serviceUploadTrajectory
bool sendPacket(crazyflie_driver::sendPacket::Request &req, crazyflie_driver::sendPacket::Response &res)
bool uploadTrajectory(crazyflie_driver::UploadTrajectory::Request &req, crazyflie_driver::UploadTrajectory::Response &res)
ros::Publisher m_pubRssi
ros::Subscriber m_subscribeCmdStop
float qz
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
static Time now()
bool land(crazyflie_driver::Land::Request &req, crazyflie_driver::Land::Response &res)
ros::Subscriber m_subscribeCmdVel
int16_t ax
CrazyflieROS(const std::string &link_uri, const std::string &tf_prefix, float roll_trim, float pitch_trim, bool enable_logging, bool enable_parameters, std::vector< crazyflie_driver::LogBlock > &log_blocks, bool use_ros_time, bool enable_logging_imu, bool enable_logging_temperature, bool enable_logging_magnetic_field, bool enable_logging_pressure, bool enable_logging_battery, bool enable_logging_pose, bool enable_logging_packets)
void positionMeasurementChanged(const geometry_msgs::PointStamped::ConstPtr &msg)
ros::ServiceServer m_serviceStop
double radToDeg(double rad)
ros::Publisher m_pubPackets
void cmdPositionSetpoint(const crazyflie_driver::Position::ConstPtr &msg)
ros::Subscriber m_subscribeCmdFullState
uint8_t header
float qx
ros::Subscriber m_subscribeCmdVelocityWorld
ros::Publisher m_pubPose
#define ROS_ERROR(...)
ros::Publisher m_pubPressure
void onLog2Data(uint32_t time_in_ms, log2 *data)
std::string m_tf_prefix


crazyflie_driver
Author(s): Wolfgang Hoenig
autogenerated on Mon Sep 28 2020 03:40:13