31 #include <sensor_msgs/Imu.h> 74 st.
stamp_ = msg->header.stamp;
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());
tf::TransformBroadcaster pub_
#define NODELET_ERROR(...)
std::string fixedFrameId_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::NodeHandle & getNodeHandle() const
ros::NodeHandle & getPrivateNodeHandle() const
geometry_msgs::TransformStamped t
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
tf::TransformListener tfListener_
#define NODELET_INFO(...)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
double waitForTransformDuration_
void imuCallback(const sensor_msgs::ImuConstPtr &msg)