Go to the documentation of this file.
31 #include <sensor_msgs/Imu.h>
84 NODELET_ERROR(
"Could not get transform from %s to %s after %f seconds (for stamp=%f)! Error=\"%s\".",
85 baseFrameId_.c_str(),
msg->header.frame_id.c_str(), 0.1,
msg->header.stamp.toSec(), errorMsg.c_str());
#define NODELET_ERROR(...)
ros::NodeHandle & getNodeHandle() const
std::string fixedFrameId_
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
double waitForTransformDuration_
ros::NodeHandle & getPrivateNodeHandle() const
void imuCallback(const sensor_msgs::ImuConstPtr &msg)
static double getYaw(const geometry_msgs::Quaternion &msg_q)
EIGEN_DEVICE_FUNC const Scalar & q
tf::TransformBroadcaster pub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
tf::TransformListener tfListener_
#define NODELET_INFO(...)
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
T param(const std::string ¶m_name, const T &default_val) const
rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50