Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
RawlogRecordNode Class Reference

ROS Node. More...

#include <rawlog_record_node.h>

Inheritance diagram for RawlogRecordNode:
Inheritance graph
[legend]

Classes

struct  ParametersNode
 

Public Member Functions

void callbackLaser (const sensor_msgs::LaserScan &)
 
void callbackMarker (const marker_msgs::MarkerDetection &)
 
void callbackOdometry (const nav_msgs::Odometry &)
 
void init ()
 
void loop ()
 
 RawlogRecordNode (ros::NodeHandle &n)
 
 ~RawlogRecordNode ()
 
- Public Member Functions inherited from RawlogRecord
 RawlogRecord ()=default
 
 ~RawlogRecord ()
 

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)
 
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_
 
ParametersNode param_ {RawlogRecord::base_param_}
 
std::map< std::string, mrpt::poses::CPose3Dstatic_tf_
 
ros::Subscriber subLaser_
 
ros::Subscriber subMarker_
 
ros::Subscriber subOdometry_
 
unsigned int sync_attempts_sensor_frame_
 

Additional Inherited Members

- Protected Member Functions inherited from RawlogRecord
void updateRawLogName (const mrpt::system::TTimeStamp &t)
 
- Protected Attributes inherited from RawlogRecord
Parameters base_param_
 
boost::interprocess::interprocess_mutex mutexRawLog
 
CRawlog pRawLog
 
CRawlog pRawLogASF
 

Detailed Description

ROS Node.

Definition at line 47 of file rawlog_record_node.h.

Constructor & Destructor Documentation

RawlogRecordNode::RawlogRecordNode ( ros::NodeHandle n)

Definition at line 57 of file rawlog_record_node.cpp.

RawlogRecordNode::~RawlogRecordNode ( )

Definition at line 56 of file rawlog_record_node.cpp.

Member Function Documentation

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 132 of file rawlog_record_node.cpp.

void RawlogRecordNode::callbackMarker ( const marker_msgs::MarkerDetection _msg)

callback function to catch motion commands

Definition at line 149 of file rawlog_record_node.cpp.

void RawlogRecordNode::callbackOdometry ( const nav_msgs::Odometry &  _msg)

Definition at line 121 of file rawlog_record_node.cpp.

void RawlogRecordNode::convert ( const nav_msgs::Odometry &  src,
mrpt::obs::CObservationOdometry des 
)
private

Definition at line 109 of file rawlog_record_node.cpp.

bool RawlogRecordNode::getStaticTF ( std::string  source_frame,
mrpt::poses::CPose3D des 
)
private

Definition at line 273 of file rawlog_record_node.cpp.

void RawlogRecordNode::init ( )

Definition at line 59 of file rawlog_record_node.cpp.

void RawlogRecordNode::loop ( )

Definition at line 77 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 79 of file rawlog_record_node.cpp.

Member Data Documentation

mrpt::obs::CObservationBeaconRanges::Ptr RawlogRecordNode::last_beacon_range_
private

Definition at line 93 of file rawlog_record_node.h.

mrpt::obs::CObservationBearingRange::Ptr RawlogRecordNode::last_bearing_range_
private

Definition at line 92 of file rawlog_record_node.h.

mrpt::obs::CObservationOdometry::Ptr RawlogRecordNode::last_odometry_
private

Definition at line 95 of file rawlog_record_node.h.

mrpt::obs::CObservation2DRangeScan::Ptr RawlogRecordNode::last_range_scan_
private

Definition at line 94 of file rawlog_record_node.h.

tf::TransformListener RawlogRecordNode::listenerTF_
private

Definition at line 91 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 98 of file rawlog_record_node.h.

ParametersNode RawlogRecordNode::param_ {RawlogRecord::base_param_}
private

Definition at line 85 of file rawlog_record_node.h.

std::map<std::string, mrpt::poses::CPose3D> RawlogRecordNode::static_tf_
private

Definition at line 97 of file rawlog_record_node.h.

ros::Subscriber RawlogRecordNode::subLaser_
private

Definition at line 88 of file rawlog_record_node.h.

ros::Subscriber RawlogRecordNode::subMarker_
private

Definition at line 89 of file rawlog_record_node.h.

ros::Subscriber RawlogRecordNode::subOdometry_
private

Definition at line 90 of file rawlog_record_node.h.

unsigned int RawlogRecordNode::sync_attempts_sensor_frame_
private

Definition at line 96 of file rawlog_record_node.h.


The documentation for this class was generated from the following files:


mrpt_rawlog
Author(s):
autogenerated on Thu Mar 12 2020 03:22:04