Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
mrpt_sensors::GenericSensorNode Class Reference

#include <mrpt_sensorlib.h>

Public Member Functions

 GenericSensorNode ()
 
virtual void init (int argc, char **argv)
 
void run ()
 
virtual ~GenericSensorNode ()
 

Protected Member Functions

virtual void init_sensor_specific ()
 
virtual void process_sensor_specific ()
 

Protected Attributes

std::string cfg_section_ {"SENSOR1"}
 
std::string cfgfilename_ {"sensor.ini"}
 
ros::NodeHandle nh_ {}
 
ros::NodeHandle nhlocal_ {"~"}
 
CFileGZOutputStream out_rawlog_
 
std::string out_rawlog_prefix_
 If non-empty, write to rawlog. More...
 
int rawlog_GZ_compress_level_ {1}
 
mrpt::hwdrivers::CGenericSensor::Ptr sensor_
 

Detailed Description

Base class for all ROS nodes that interface an MRPT sensor. Provides the basic initialization of the sensor, parsing of incoming data, etc. Derived classes only have to worry about converting the observations to ROS msgs and expose any sensor-specific messages and services.

Definition at line 22 of file mrpt_sensorlib.h.

Constructor & Destructor Documentation

GenericSensorNode::GenericSensorNode ( )

Definition at line 17 of file mrpt_sensorlib.cpp.

GenericSensorNode::~GenericSensorNode ( )
virtual

Definition at line 19 of file mrpt_sensorlib.cpp.

Member Function Documentation

void GenericSensorNode::init ( int  argc,
char **  argv 
)
virtual

Load parameters and establish communication with the sensor

Definition at line 21 of file mrpt_sensorlib.cpp.

virtual void mrpt_sensors::GenericSensorNode::init_sensor_specific ( )
inlineprotectedvirtual

Definition at line 36 of file mrpt_sensorlib.h.

virtual void mrpt_sensors::GenericSensorNode::process_sensor_specific ( )
inlineprotectedvirtual

Definition at line 33 of file mrpt_sensorlib.h.

void GenericSensorNode::run ( )

Infinite loop for main().

Definition at line 88 of file mrpt_sensorlib.cpp.

Member Data Documentation

std::string mrpt_sensors::GenericSensorNode::cfg_section_ {"SENSOR1"}
protected

Definition at line 27 of file mrpt_sensorlib.h.

std::string mrpt_sensors::GenericSensorNode::cfgfilename_ {"sensor.ini"}
protected

Definition at line 27 of file mrpt_sensorlib.h.

ros::NodeHandle mrpt_sensors::GenericSensorNode::nh_ {}
protected

Definition at line 25 of file mrpt_sensorlib.h.

ros::NodeHandle mrpt_sensors::GenericSensorNode::nhlocal_ {"~"}
protected

Definition at line 26 of file mrpt_sensorlib.h.

CFileGZOutputStream mrpt_sensors::GenericSensorNode::out_rawlog_
protected

Definition at line 30 of file mrpt_sensorlib.h.

std::string mrpt_sensors::GenericSensorNode::out_rawlog_prefix_
protected

If non-empty, write to rawlog.

Definition at line 29 of file mrpt_sensorlib.h.

int mrpt_sensors::GenericSensorNode::rawlog_GZ_compress_level_ {1}
protected

Definition at line 31 of file mrpt_sensorlib.h.

mrpt::hwdrivers::CGenericSensor::Ptr mrpt_sensors::GenericSensorNode::sensor_
protected

Definition at line 28 of file mrpt_sensorlib.h.


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


mrpt_sensorlib
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jul 16 2020 03:15:20