34 #ifndef MRPT_RAWLOG_RECORD_NODE_H 35 #define MRPT_RAWLOG_RECORD_NODE_H 39 #include <nav_msgs/Odometry.h> 40 #include <sensor_msgs/LaserScan.h> 41 #include <marker_msgs/MarkerDetection.h> 42 #include <dynamic_reconfigure/server.h> 43 #include "mrpt_rawlog/RawLogRecordConfig.h" 61 dynamic_reconfigure::Server<mrpt_rawlog::RawLogRecordConfig>
63 dynamic_reconfigure::Server<
65 void update(
const unsigned long& loop_count);
102 const std::string& source_frame,
const ros::Time& time,
110 #endif // MRPT_RAWLOG_RECORD_NODE_H unsigned int sync_attempts_sensor_frame_
mrpt::obs::CObservationBearingRange::Ptr last_bearing_range_
bool getStaticTF(std::string source_frame, mrpt::poses::CPose3D &des)
void callbackLaser(const sensor_msgs::LaserScan &)
ParametersNode(RawlogRecord::Parameters &base_params)
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig >::CallbackType reconfigureFnc_
double sensor_frame_sync_threshold
RawlogRecord::Parameters & base_param_
bool waitForTransform(mrpt::poses::CPose3D &des, const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01))
static const int MOTION_MODEL_GAUSSIAN
ros::Subscriber subOdometry_
std::string odom_frame_id
mrpt::obs::CObservation2DRangeScan::Ptr last_range_scan_
std::string base_frame_id
static const int MOTION_MODEL_THRUN
void convert(const nav_msgs::Odometry &src, mrpt::obs::CObservationOdometry &des)
tf::TransformListener listenerTF_
std::map< std::string, mrpt::poses::CPose3D > static_tf_
void addObservation(const ros::Time &time)
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig > reconfigureServer_
void callbackOdometry(const nav_msgs::Odometry &)
mrpt::obs::CObservationBeaconRanges::Ptr last_beacon_range_
mrpt::obs::CObservationOdometry::Ptr last_odometry_
ros::Subscriber subLaser_
int parameter_update_skip
RawlogRecordNode(ros::NodeHandle &n)
void callbackMarker(const marker_msgs::MarkerDetection &)
void update(const unsigned long &loop_count)
void callbackParameters(mrpt_rawlog::RawLogRecordConfig &config, uint32_t level)
ros::Subscriber subMarker_