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" 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" 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" 46 constexpr
double pi() {
return 3.141592653589793238462643383279502884; }
49 return deg / 180.0 *
pi();
53 return rad * 180.0 /
pi();
66 virtual void info(
const std::string& msg)
71 virtual void warning(
const std::string& msg)
76 virtual void error(
const std::string& msg)
88 const std::string& link_uri,
89 const std::string& tf_prefix,
93 bool enable_parameters,
94 std::vector<crazyflie_driver::LogBlock>& log_blocks,
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)
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()
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()
145 , m_sentSetpoint(false)
146 , m_sentExternalPosition(false)
154 m_isEmergency =
true;
165 crazyflie_driver::sendPacket::Request &req,
166 crazyflie_driver::sendPacket::Response &res)
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];
175 m_cf.queueOutgoingPacket(packet);
207 std_srvs::Empty::Request& req,
208 std_srvs::Empty::Response& res)
211 m_isEmergency =
true;
212 m_cf.emergencyStop();
217 template<
class T,
class U>
221 m_cf.setParam<T>(id, (T)value);
225 const crazyflie_driver::Hover::ConstPtr& msg)
228 if (!m_isEmergency) {
234 m_cf.sendHoverSetpoint(vx, vy, yawRate, zDistance);
235 m_sentSetpoint =
true;
241 const std_msgs::Empty::ConstPtr& msg)
244 if (!m_isEmergency) {
246 m_sentSetpoint =
true;
252 const crazyflie_driver::Position::ConstPtr& msg)
258 float yaw = msg->yaw;
260 m_cf.sendPositionSetpoint(x, y, z, yaw);
261 m_sentSetpoint =
true;
266 crazyflie_driver::UpdateParams::Request& req,
267 crazyflie_driver::UpdateParams::Response& res)
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());
276 auto entry = m_cf.getParamTocEntry(
group,
name);
279 switch (entry->type) {
281 updateParam<uint8_t, int>(entry->id, ros_param);
284 updateParam<int8_t, int>(entry->id, ros_param);
287 updateParam<uint16_t, int>(entry->id, ros_param);
290 updateParam<int16_t, int>(entry->id, ros_param);
293 updateParam<uint32_t, int>(entry->id, ros_param);
296 updateParam<int32_t, int>(entry->id, ros_param);
299 updateParam<float, float>(entry->id, ros_param);
311 const geometry_msgs::Twist::ConstPtr& msg)
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);
319 m_cf.sendSetpoint(roll, pitch, yawrate, thrust);
320 m_sentSetpoint =
true;
325 const crazyflie_driver::FullState::ConstPtr& msg)
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;
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;
347 m_cf.sendFullStateSetpoint(
352 rollRate, pitchRate, yawRate);
353 m_sentSetpoint =
true;
359 const crazyflie_driver::VelocityWorld::ConstPtr& msg)
362 if (!m_isEmergency) {
363 float x = msg->vel.x;
364 float y = msg->vel.y;
365 float z = msg->vel.z;
368 m_cf.sendVelocityWorldSetpoint(
370 m_sentSetpoint =
true;
376 const geometry_msgs::PointStamped::ConstPtr& msg)
378 m_cf.sendExternalPositionUpdate(msg->point.x, msg->point.y, msg->point.z);
379 m_sentExternalPosition =
true;
383 const geometry_msgs::PoseStamped::ConstPtr& msg)
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;
416 if (m_enable_logging_imu) {
417 m_pubImu = n.
advertise<sensor_msgs::Imu>(m_tf_prefix +
"/imu", 10);
419 if (m_enable_logging_temperature) {
420 m_pubTemp = n.
advertise<sensor_msgs::Temperature>(m_tf_prefix +
"/temperature", 10);
422 if (m_enable_logging_magnetic_field) {
423 m_pubMag = n.
advertise<sensor_msgs::MagneticField>(m_tf_prefix +
"/magnetic_field", 10);
425 if (m_enable_logging_pressure) {
426 m_pubPressure = n.
advertise<std_msgs::Float32>(m_tf_prefix +
"/pressure", 10);
428 if (m_enable_logging_battery) {
429 m_pubBattery = n.
advertise<std_msgs::Float32>(m_tf_prefix +
"/battery", 10);
431 if (m_enable_logging_pose) {
432 m_pubPose = n.
advertise<geometry_msgs::PoseStamped>(m_tf_prefix +
"/pose", 10);
434 if (m_enable_logging_packets) {
435 m_pubPackets = n.
advertise<crazyflie_driver::crtpPacket>(m_tf_prefix +
"/packets", 10);
437 m_cf.setGenericPacketCallback(cb_genericPacket);
439 m_pubRssi = n.
advertise<std_msgs::Float32>(m_tf_prefix +
"/rssi", 10);
441 for (
auto& logBlock : m_logBlocks)
443 m_pubLogDataGeneric.push_back(n.
advertise<crazyflie_driver::GenericLogData>(m_tf_prefix +
"/" + logBlock.topic_name, 10));
450 auto start = std::chrono::system_clock::now();
455 m_cf.setLinkQualityCallback(cb_lq);
457 if (m_enableParameters)
460 m_cf.requestParamToc();
461 for (
auto iter = m_cf.paramsBegin(); iter != m_cf.paramsEnd(); ++iter) {
463 std::string paramName =
"/" + m_tf_prefix +
"/" + entry.group +
"/" + entry.name;
464 switch (entry.type) {
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) {
497 std::function<void(const crtpPlatformRSSIAck*)> cb_ack = std::bind(&
CrazyflieROS::onEmptyAck,
this, std::placeholders::_1);
498 m_cf.setEmptyAckCallback(cb_ack);
501 m_cf.requestLogToc();
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);
515 logBlockImu->start(1);
518 if ( m_enable_logging_temperature
519 || m_enable_logging_magnetic_field
520 || m_enable_logging_pressure
521 || m_enable_logging_battery)
523 std::function<void(uint32_t, log2*)> cb2 = std::bind(&
CrazyflieROS::onLog2Data,
this, std::placeholders::_1, std::placeholders::_2);
531 {
"baro",
"pressure"},
534 logBlock2->start(10);
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);
542 {
"stateEstimate",
"x"},
543 {
"stateEstimate",
"y"},
544 {
"stateEstimate",
"z"},
545 {
"stateEstimateZ",
"quat"}
547 logBlockPose->start(1);
552 for (
auto& logBlock : m_logBlocks)
554 std::function<void(uint32_t, std::vector<double>*,
void* userData)> cb =
558 std::placeholders::_1,
559 std::placeholders::_2,
560 std::placeholders::_3);
565 (
void*)&m_pubLogDataGeneric[i],
567 logBlocksGeneric[i]->start(logBlock.frequency / 10);
575 m_cf.requestMemoryToc();
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());
583 for (
int i = 0; i < 100; ++i) {
584 m_cf.sendSetpoint(0, 0, 0, 0);
587 while(!m_isEmergency) {
589 if (m_enableLogging && !m_sentSetpoint && !m_sentExternalPosition) {
590 m_cf.transmitPackets();
593 m_sentSetpoint =
false;
594 m_sentExternalPosition =
false;
598 std::this_thread::sleep_for(std::chrono::milliseconds(1));
602 for (
int i = 0; i < 100; ++i) {
603 m_cf.sendSetpoint(0, 0, 0, 0);
609 if (m_enable_logging_imu) {
610 sensor_msgs::Imu
msg;
611 if (m_use_ros_time) {
614 msg.header.stamp =
ros::Time(time_in_ms / 1000.0);
616 msg.header.frame_id = m_tf_prefix +
"/base_link";
617 msg.orientation_covariance[0] = -1;
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;
629 m_pubImu.publish(msg);
635 if (m_enable_logging_temperature) {
636 sensor_msgs::Temperature
msg;
637 if (m_use_ros_time) {
640 msg.header.stamp =
ros::Time(time_in_ms / 1000.0);
642 msg.header.frame_id = m_tf_prefix +
"/base_link";
645 m_pubTemp.publish(msg);
648 if (m_enable_logging_magnetic_field) {
649 sensor_msgs::MagneticField
msg;
650 if (m_use_ros_time) {
653 msg.header.stamp =
ros::Time(time_in_ms / 1000.0);
655 msg.header.frame_id = m_tf_prefix +
"/base_link";
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);
664 if (m_enable_logging_pressure) {
665 std_msgs::Float32
msg;
668 m_pubPressure.publish(msg);
671 if (m_enable_logging_battery) {
672 std_msgs::Float32
msg;
675 m_pubBattery.publish(msg);
680 if (m_enable_logging_pose) {
681 geometry_msgs::PoseStamped
msg;
682 if (m_use_ros_time) {
685 msg.header.stamp =
ros::Time(time_in_ms / 1000.0);
687 msg.header.frame_id = m_tf_prefix +
"/base_link";
689 msg.pose.position.x = data->
x;
690 msg.pose.position.y = data->
y;
691 msg.pose.position.z = data->
z;
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];
700 m_pubPose.publish(msg);
704 void onLogCustom(uint32_t time_in_ms, std::vector<double>* values,
void* userData) {
708 crazyflie_driver::GenericLogData
msg;
709 if (m_use_ros_time) {
712 msg.header.stamp =
ros::Time(time_in_ms / 1000.0);
714 msg.header.frame_id = m_tf_prefix +
"/base_link";
715 msg.values = *values;
721 std_msgs::Float32
msg;
723 msg.data = data->
rssi;
724 m_pubRssi.publish(msg);
728 if (linkQuality < 0.7) {
729 ROS_WARN_NAMED(m_tf_prefix,
"Link Quality low (%f)", linkQuality);
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);
745 crazyflie_driver::crtpPacket packet;
747 packet.header = ack.
data[0];
748 memcpy(&packet.data[0], &ack.
data[1], ack.
size);
749 m_pubPackets.publish(packet);
753 crazyflie_driver::SetGroupMask::Request& req,
754 crazyflie_driver::SetGroupMask::Response& res)
757 m_cf.setGroupMask(req.groupMask);
762 crazyflie_driver::Takeoff::Request& req,
763 crazyflie_driver::Takeoff::Response& res)
766 m_cf.takeoff(req.height, req.duration.toSec(), req.groupMask);
771 crazyflie_driver::Land::Request& req,
772 crazyflie_driver::Land::Response& res)
775 m_cf.land(req.height, req.duration.toSec(), req.groupMask);
780 crazyflie_driver::Stop::Request& req,
781 crazyflie_driver::Stop::Response& res)
784 m_cf.stop(req.groupMask);
789 crazyflie_driver::GoTo::Request& req,
790 crazyflie_driver::GoTo::Response& res)
793 m_cf.goTo(req.goal.x, req.goal.y, req.goal.z, req.yaw, req.duration.toSec(), req.relative, req.groupMask);
798 crazyflie_driver::UploadTrajectory::Request& req,
799 crazyflie_driver::UploadTrajectory::Response& res)
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) {
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];
820 m_cf.uploadTrajectory(req.trajectoryId, req.pieceOffset, pieces);
827 crazyflie_driver::StartTrajectory::Request& req,
828 crazyflie_driver::StartTrajectory::Response& res)
831 m_cf.startTrajectory(req.trajectoryId, req.timescale, req.reversed, req.relative, req.groupMask);
836 crazyflie_driver::NotifySetpointsStop::Request& req,
837 crazyflie_driver::NotifySetpointsStop::Response& res)
840 m_cf.notifySetpointsStop(req.remainValidMillisecs);
927 std::this_thread::sleep_for(std::chrono::milliseconds(1));
934 crazyflie_driver::AddCrazyflie::Request &req,
935 crazyflie_driver::AddCrazyflie::Response &res)
937 ROS_INFO(
"Adding %s as %s with trim(%f, %f). Logging: %d, Parameters: %d, Use ROS time: %d",
939 req.tf_prefix.c_str(),
942 req.enable_parameters,
947 if (m_crazyflies.find(req.uri) != m_crazyflies.end()) {
948 ROS_ERROR(
"Cannot add %s, already added.", req.uri.c_str());
958 req.enable_parameters,
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);
969 m_crazyflies[req.uri] = cf;
975 crazyflie_driver::RemoveCrazyflie::Request &req,
976 crazyflie_driver::RemoveCrazyflie::Response &res)
979 if (m_crazyflies.find(req.uri) == m_crazyflies.end()) {
980 ROS_ERROR(
"Cannot remove %s, not connected.", req.uri.c_str());
984 ROS_INFO(
"Removing crazyflie at uri %s.", req.uri.c_str());
986 m_crazyflies[req.uri]->stop();
987 delete m_crazyflies[req.uri];
988 m_crazyflies.erase(req.uri);
990 ROS_INFO(
"Crazyflie %s removed.", req.uri.c_str());
1051 ros::init(argc, argv,
"crazyflie_server");
bool emergency(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool m_enable_logging_magnetic_field
double degToRad(double deg)
void quatdecompress(uint32_t comp, float q[4])
#define ROS_INFO_NAMED(name,...)
void onGenericPacket(const ITransport::Ack &ack)
ros::ServiceServer m_serviceTakeoff
void cmdVelChanged(const geometry_msgs::Twist::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
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
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)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool remove_crazyflie(crazyflie_driver::RemoveCrazyflie::Request &req, crazyflie_driver::RemoveCrazyflie::Response &res)
ros::ServiceServer m_sendPacketServer
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)
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
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)
ros::CallbackQueue m_callback_queue
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)
void cmdFullStateSetpoint(const crazyflie_driver::FullState::ConstPtr &msg)
ros::Subscriber m_subscribeCmdPosition
ROSCPP_DECL bool get(const std::string &key, std::string &s)
bool m_enable_logging_imu
ros::ServiceServer m_serviceGoTo
void onLinkQuality(float linkQuality)
ros::ServiceServer m_serviceStartTrajectory
void setCallbackQueue(CallbackQueueInterface *queue)
bool m_enable_logging_pressure
void updateParam(uint16_t id, const std::string &ros_param)
bool takeoff(crazyflie_driver::Takeoff::Request &req, crazyflie_driver::Takeoff::Response &res)
virtual void warning(const std::string &msg)
bool m_enable_logging_packets
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)
virtual void info(const std::string &msg)
ros::ServiceServer m_serviceUpdateParams
int main(int argc, char **argv)
ros::Subscriber m_subscribeCmdHover
void cmdVelocityWorldSetpoint(const crazyflie_driver::VelocityWorld::ConstPtr &msg)
static ROSLogger rosLogger
bool m_enable_logging_battery
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::Subscriber m_subscribeCmdStop
bool m_enable_logging_pose
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
bool land(crazyflie_driver::Land::Request &req, crazyflie_driver::Land::Response &res)
ros::Subscriber m_subscribeCmdVel
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
ros::Subscriber m_subscribeCmdVelocityWorld
ros::Publisher m_pubPressure
void onLog2Data(uint32_t time_in_ms, log2 *data)