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

#include <mrpt_sensorlib.h>

Public Member Functions

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

Protected Member Functions

virtual void init_sensor_specific ()
 
virtual void internal_init ()
 
virtual void on_observation (const mrpt::obs::CObservation::Ptr &o)
 
virtual void on_observation_velodyne (const mrpt::obs::CObservationVelodyneScan &o)
 
virtual void process_sensor_specific ()
 

Protected Attributes

std::string cfg_section_ {"SENSOR1"}
 
std::shared_ptr< mrpt::config::CConfigFileBase > cfgfile_
 
std::optional< std::string > cfgfilename_
 
ros::NodeHandle nh_ {}
 
ros::NodeHandle nhlocal_ {"~"}
 
mrpt::io::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::GenericSensorNode ( )

Definition at line 23 of file mrpt_sensorlib.cpp.

◆ ~GenericSensorNode()

GenericSensorNode::~GenericSensorNode ( )
virtual

Definition at line 25 of file mrpt_sensorlib.cpp.

Member Function Documentation

◆ init_from_config_file()

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

Load parameters and establish communication with the sensor

Definition at line 90 of file mrpt_sensorlib.cpp.

◆ init_from_template_and_parameters()

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

Definition at line 114 of file mrpt_sensorlib.cpp.

◆ init_sensor_specific()

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

Definition at line 55 of file mrpt_sensorlib.h.

◆ internal_init()

void GenericSensorNode::internal_init ( )
protectedvirtual

Uses cfgfile_ and cfg_section_

Definition at line 27 of file mrpt_sensorlib.cpp.

◆ on_observation()

void GenericSensorNode::on_observation ( const mrpt::obs::CObservation::Ptr &  o)
protectedvirtual

Process each observation and publish it to ROS topic

Definition at line 199 of file mrpt_sensorlib.cpp.

◆ on_observation_velodyne()

void GenericSensorNode::on_observation_velodyne ( const mrpt::obs::CObservationVelodyneScan &  o)
protectedvirtual

Definition at line 217 of file mrpt_sensorlib.cpp.

◆ process_sensor_specific()

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

Definition at line 52 of file mrpt_sensorlib.h.

◆ run()

void GenericSensorNode::run ( )

Infinite loop for main().

Definition at line 161 of file mrpt_sensorlib.cpp.

Member Data Documentation

◆ cfg_section_

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

Definition at line 42 of file mrpt_sensorlib.h.

◆ cfgfile_

std::shared_ptr<mrpt::config::CConfigFileBase> mrpt_sensorlib::GenericSensorNode::cfgfile_
protected

Definition at line 41 of file mrpt_sensorlib.h.

◆ cfgfilename_

std::optional<std::string> mrpt_sensorlib::GenericSensorNode::cfgfilename_
protected

Definition at line 40 of file mrpt_sensorlib.h.

◆ nh_

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

Definition at line 37 of file mrpt_sensorlib.h.

◆ nhlocal_

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

Definition at line 38 of file mrpt_sensorlib.h.

◆ out_rawlog_

mrpt::io::CFileGZOutputStream mrpt_sensorlib::GenericSensorNode::out_rawlog_
protected

Definition at line 46 of file mrpt_sensorlib.h.

◆ out_rawlog_prefix_

std::string mrpt_sensorlib::GenericSensorNode::out_rawlog_prefix_
protected

If non-empty, write to rawlog.

Definition at line 45 of file mrpt_sensorlib.h.

◆ rawlog_GZ_compress_level_

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

Definition at line 47 of file mrpt_sensorlib.h.

◆ sensor_

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

Definition at line 44 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 Fri Jun 16 2023 02:35:27