ROS Node. More...
#include <rawlog_record_node.h>

Classes | |
| struct | ParametersNode |
Public Member Functions | |
| void | callbackLaser (const sensor_msgs::LaserScan &) |
| void | callbackMarker (const marker_msgs::MarkerDetection &) |
| callback function to catch motion commands | |
| void | callbackOdometry (const nav_msgs::Odometry &) |
| void | init () |
| void | loop () |
| RawlogRecordNode (ros::NodeHandle &n) | |
| ~RawlogRecordNode () | |
Private Member Functions | |
| void | addObservation (const ros::Time &time) |
| void | convert (const nav_msgs::Odometry &src, mrpt::obs::CObservationOdometry &des) |
| bool | getStaticTF (std::string source_frame, mrpt::poses::CPose3D &des) |
| ParametersNode * | param () |
| void | update () |
| 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)) |
Private Attributes | |
| mrpt::obs::CObservationBeaconRanges::Ptr | last_beacon_range_ |
| mrpt::obs::CObservationBearingRange::Ptr | last_bearing_range_ |
| mrpt::obs::CObservationOdometry::Ptr | last_odometry_ |
| mrpt::obs::CObservation2DRangeScan::Ptr | last_range_scan_ |
| tf::TransformListener | listenerTF_ |
| MRPT_ROS_LOG_MACROS | |
| ros::NodeHandle | n_ |
| std::map< std::string, mrpt::poses::CPose3D > | static_tf_ |
| ros::Subscriber | subLaser_ |
| ros::Subscriber | subMarker_ |
| ros::Subscriber | subOdometry_ |
| unsigned int | sync_attempts_sensor_frame_ |
ROS Node.
Definition at line 47 of file rawlog_record_node.h.
Definition at line 57 of file rawlog_record_node.cpp.
Definition at line 56 of file rawlog_record_node.cpp.
| void RawlogRecordNode::addObservation | ( | const ros::Time & | time | ) | [private] |
Definition at line 177 of file rawlog_record_node.cpp.
| void RawlogRecordNode::callbackLaser | ( | const sensor_msgs::LaserScan & | _msg | ) |
Definition at line 137 of file rawlog_record_node.cpp.
| void RawlogRecordNode::callbackMarker | ( | const marker_msgs::MarkerDetection & | _msg | ) |
callback function to catch motion commands
Definition at line 153 of file rawlog_record_node.cpp.
| void RawlogRecordNode::callbackOdometry | ( | const nav_msgs::Odometry & | _msg | ) |
Definition at line 126 of file rawlog_record_node.cpp.
| void RawlogRecordNode::convert | ( | const nav_msgs::Odometry & | src, |
| mrpt::obs::CObservationOdometry & | des | ||
| ) | [private] |
Definition at line 116 of file rawlog_record_node.cpp.
| bool RawlogRecordNode::getStaticTF | ( | std::string | source_frame, |
| mrpt::poses::CPose3D & | des | ||
| ) | [private] |
Definition at line 259 of file rawlog_record_node.cpp.
| void RawlogRecordNode::init | ( | ) |
Definition at line 68 of file rawlog_record_node.cpp.
| void RawlogRecordNode::loop | ( | ) |
Definition at line 81 of file rawlog_record_node.cpp.
| RawlogRecordNode::ParametersNode * RawlogRecordNode::param | ( | ) | [private] |
Definition at line 63 of file rawlog_record_node.cpp.
| void RawlogRecordNode::update | ( | ) | [private] |
| bool RawlogRecordNode::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) |
||
| ) | [private] |
Definition at line 86 of file rawlog_record_node.cpp.
mrpt::obs::CObservationBeaconRanges::Ptr RawlogRecordNode::last_beacon_range_ [private] |
Definition at line 90 of file rawlog_record_node.h.
mrpt::obs::CObservationBearingRange::Ptr RawlogRecordNode::last_bearing_range_ [private] |
Definition at line 89 of file rawlog_record_node.h.
mrpt::obs::CObservationOdometry::Ptr RawlogRecordNode::last_odometry_ [private] |
Definition at line 92 of file rawlog_record_node.h.
mrpt::obs::CObservation2DRangeScan::Ptr RawlogRecordNode::last_range_scan_ [private] |
Definition at line 91 of file rawlog_record_node.h.
Definition at line 88 of file rawlog_record_node.h.
RawlogRecordNode::MRPT_ROS_LOG_MACROS [private] |
Definition at line 49 of file rawlog_record_node.h.
ros::NodeHandle RawlogRecordNode::n_ [private] |
Definition at line 95 of file rawlog_record_node.h.
std::map<std::string, mrpt::poses::CPose3D> RawlogRecordNode::static_tf_ [private] |
Definition at line 94 of file rawlog_record_node.h.
ros::Subscriber RawlogRecordNode::subLaser_ [private] |
Definition at line 85 of file rawlog_record_node.h.
ros::Subscriber RawlogRecordNode::subMarker_ [private] |
Definition at line 86 of file rawlog_record_node.h.
Definition at line 87 of file rawlog_record_node.h.
unsigned int RawlogRecordNode::sync_attempts_sensor_frame_ [private] |
Definition at line 93 of file rawlog_record_node.h.