Go to the documentation of this file.
34 #ifndef MRPT_RAWLOG_RECORD_NODE_H
35 #define MRPT_RAWLOG_RECORD_NODE_H
37 #include <dynamic_reconfigure/server.h>
38 #include <marker_msgs/MarkerDetection.h>
39 #include <nav_msgs/Odometry.h>
41 #include <sensor_msgs/LaserScan.h>
43 #include "mrpt_rawlog/RawLogRecordConfig.h"
62 mrpt_rawlog::RawLogRecordConfig& config, uint32_t level);
63 dynamic_reconfigure::Server<mrpt_rawlog::RawLogRecordConfig>
65 dynamic_reconfigure::Server<
67 void update(
const unsigned long& loop_count);
80 const sensor_msgs::LaserScan&);
88 bool getStaticTF(std::string source_frame, mrpt::poses::CPose3D& des);
101 std::map<std::string, mrpt::poses::CPose3D>
static_tf_;
105 mrpt::poses::CPose3D& des,
const std::string& target_frame,
106 const std::string& source_frame,
const ros::Time& time,
111 const nav_msgs::Odometry& src, mrpt::obs::CObservationOdometry& des);
114 #endif // MRPT_RAWLOG_RECORD_NODE_H
void update(const unsigned long &loop_count)
std::map< std::string, mrpt::poses::CPose3D > static_tf_
void callbackOdometry(const nav_msgs::Odometry &)
ros::Subscriber subLaser_
double sensor_frame_sync_threshold
RawlogRecord::Parameters & base_param_
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig >::CallbackType reconfigureFnc_
mrpt::obs::CObservationBeaconRanges::Ptr last_beacon_range_
ParametersNode(RawlogRecord::Parameters &base_params)
static const int MOTION_MODEL_GAUSSIAN
RawlogRecordNode(ros::NodeHandle &n)
void callbackMarker(const marker_msgs::MarkerDetection &)
commands
tf2_ros::Buffer tf_buffer_
void addObservation(const ros::Time &time)
void convert(const nav_msgs::Odometry &src, mrpt::obs::CObservationOdometry &des)
std::string base_frame_id
bool getStaticTF(std::string source_frame, mrpt::poses::CPose3D &des)
tf2_ros::TransformListener listenerTF_
mrpt::obs::CObservationOdometry::Ptr last_odometry_
void callbackLaser(const sensor_msgs::LaserScan &)
mrpt::obs::CObservationBearingRange::Ptr last_bearing_range_
std::string odom_frame_id
static const int MOTION_MODEL_THRUN
ros::Subscriber subMarker_
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig > reconfigureServer_
ros::Subscriber subOdometry_
mrpt::obs::CObservation2DRangeScan::Ptr last_range_scan_
unsigned int sync_attempts_sensor_frame_
void callbackParameters(mrpt_rawlog::RawLogRecordConfig &config, uint32_t level)
int parameter_update_skip
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))
mrpt_rawlog
Author(s):
autogenerated on Tue Sep 17 2024 02:10:22