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

Classes

struct  TAuxInitializer
 
struct  TInfoPerTimeStep
 

Public Member Functions

 LocalObstaclesNode (int argc, char **argv)
 

Private Types

typedef std::multimap< double, TInfoPerTimeStepTListObservations
 

Private Member Functions

void onDoPublish (const ros::TimerEvent &)
 
void onNewSensor_Laser2D (const sensor_msgs::LaserScanConstPtr &scan)
 
void onNewSensor_PointCloud (const sensor_msgs::PointCloud2::ConstPtr &pts)
 
template<typename CALLBACK_METHOD_TYPE >
size_t subscribeToMultipleTopics (const std::string &lstTopics, std::vector< ros::Subscriber > &subs, CALLBACK_METHOD_TYPE cb)
 Subscribe to a variable number of topics. More...
 

Private Attributes

TAuxInitializer m_auxinit
 Just to make sure ROS is init first. More...
 
std::string m_filter_output_layer_name
 mp2p_icp output layer name More...
 
mp2p_icp_filters::FilterPipeline m_filter_pipeline
 
std::string m_frameid_reference = "odom"
 
std::string m_frameid_robot = "base_link"
 
mrpt::gui::CDisplayWindow3D::Ptr m_gui_win
 
TListObservations m_hist_obs
 
boost::mutex m_hist_obs_mtx
 the interest time window. More...
 
CSimplePointsMap::Ptr m_localmap_pts = CSimplePointsMap::Create()
 
ros::NodeHandle m_localn
 "~" More...
 
ros::NodeHandle m_nh
 The node handle. More...
 
CTimeLogger m_profiler
 
double m_publish_period = 0.05
 [s] More...
 
bool m_show_gui = true
 
std::string m_source_topics_2dscan = "scan,laser1"
 
std::string m_source_topics_pointclouds = ""
 
double m_time_window = 0.20
 [s]can't be smaller than m_publish_period More...
 
ros::Timer m_timer_publish
 
std::string m_topic_local_map_pointcloud = "local_map_pointcloud"
 
ROS pubs/subs
ros::Publisher m_pub_local_map_pointcloud
 Subscriber to 2D laser scans. More...
 
std::vector< ros::Subscriberm_subs_2dlaser
 Subscriber to point cloud sensors. More...
 
std::vector< ros::Subscriberm_subs_pointclouds
 
tf2_ros::Buffer m_tf_buffer
 
tf2_ros::TransformListener m_tf_listener {m_tf_buffer}
 

Detailed Description

Definition at line 66 of file mrpt_local_obstacles_node.cpp.

Member Typedef Documentation

◆ TListObservations

typedef std::multimap<double, TInfoPerTimeStep> LocalObstaclesNode::TListObservations
private

Definition at line 104 of file mrpt_local_obstacles_node.cpp.

Constructor & Destructor Documentation

◆ LocalObstaclesNode()

LocalObstaclesNode::LocalObstaclesNode ( int  argc,
char **  argv 
)
inline

Constructor: Inits ROS system

Definition at line 530 of file mrpt_local_obstacles_node.cpp.

Member Function Documentation

◆ onDoPublish()

void LocalObstaclesNode::onDoPublish ( const ros::TimerEvent )
inlineprivate

Callback: On recalc local map & publish it

Definition at line 346 of file mrpt_local_obstacles_node.cpp.

◆ onNewSensor_Laser2D()

void LocalObstaclesNode::onNewSensor_Laser2D ( const sensor_msgs::LaserScanConstPtr &  scan)
inlineprivate

Callback: On new sensor data

Definition at line 157 of file mrpt_local_obstacles_node.cpp.

◆ onNewSensor_PointCloud()

void LocalObstaclesNode::onNewSensor_PointCloud ( const sensor_msgs::PointCloud2::ConstPtr &  pts)
inlineprivate

Callback: On new sensor data

Definition at line 251 of file mrpt_local_obstacles_node.cpp.

◆ subscribeToMultipleTopics()

template<typename CALLBACK_METHOD_TYPE >
size_t LocalObstaclesNode::subscribeToMultipleTopics ( const std::string &  lstTopics,
std::vector< ros::Subscriber > &  subs,
CALLBACK_METHOD_TYPE  cb 
)
inlineprivate

Subscribe to a variable number of topics.

Parameters
lstTopicsString with list of topics separated with ","
subs[in,out]List of subscribers will be here at return.
Returns
The number of topics subscribed to.

Definition at line 143 of file mrpt_local_obstacles_node.cpp.

Member Data Documentation

◆ m_auxinit

TAuxInitializer LocalObstaclesNode::m_auxinit
private

Just to make sure ROS is init first.

Definition at line 79 of file mrpt_local_obstacles_node.cpp.

◆ m_filter_output_layer_name

std::string LocalObstaclesNode::m_filter_output_layer_name
private

mp2p_icp output layer name

Definition at line 117 of file mrpt_local_obstacles_node.cpp.

◆ m_filter_pipeline

mp2p_icp_filters::FilterPipeline LocalObstaclesNode::m_filter_pipeline
private

Used for example to run voxel grid decimation, etc. Refer to mp2p_icp docs

Definition at line 115 of file mrpt_local_obstacles_node.cpp.

◆ m_frameid_reference

std::string LocalObstaclesNode::m_frameid_reference = "odom"
private

Definition at line 85 of file mrpt_local_obstacles_node.cpp.

◆ m_frameid_robot

std::string LocalObstaclesNode::m_frameid_robot = "base_link"
private

Definition at line 86 of file mrpt_local_obstacles_node.cpp.

◆ m_gui_win

mrpt::gui::CDisplayWindow3D::Ptr LocalObstaclesNode::m_gui_win
private

Definition at line 119 of file mrpt_local_obstacles_node.cpp.

◆ m_hist_obs

TListObservations LocalObstaclesNode::m_hist_obs
private

The history of past observations during

Definition at line 105 of file mrpt_local_obstacles_node.cpp.

◆ m_hist_obs_mtx

boost::mutex LocalObstaclesNode::m_hist_obs_mtx
private

the interest time window.

Definition at line 107 of file mrpt_local_obstacles_node.cpp.

◆ m_localmap_pts

CSimplePointsMap::Ptr LocalObstaclesNode::m_localmap_pts = CSimplePointsMap::Create()
private

The local maps

Definition at line 110 of file mrpt_local_obstacles_node.cpp.

◆ m_localn

ros::NodeHandle LocalObstaclesNode::m_localn
private

"~"

Definition at line 81 of file mrpt_local_obstacles_node.cpp.

◆ m_nh

ros::NodeHandle LocalObstaclesNode::m_nh
private

The node handle.

Definition at line 80 of file mrpt_local_obstacles_node.cpp.

◆ m_profiler

CTimeLogger LocalObstaclesNode::m_profiler
private

Definition at line 77 of file mrpt_local_obstacles_node.cpp.

◆ m_pub_local_map_pointcloud

ros::Publisher LocalObstaclesNode::m_pub_local_map_pointcloud
private

Subscriber to 2D laser scans.

Definition at line 123 of file mrpt_local_obstacles_node.cpp.

◆ m_publish_period

double LocalObstaclesNode::m_publish_period = 0.05
private

[s]

Definition at line 94 of file mrpt_local_obstacles_node.cpp.

◆ m_show_gui

bool LocalObstaclesNode::m_show_gui = true
private

Definition at line 83 of file mrpt_local_obstacles_node.cpp.

◆ m_source_topics_2dscan

std::string LocalObstaclesNode::m_source_topics_2dscan = "scan,laser1"
private

Definition at line 90 of file mrpt_local_obstacles_node.cpp.

◆ m_source_topics_pointclouds

std::string LocalObstaclesNode::m_source_topics_pointclouds = ""
private

Definition at line 91 of file mrpt_local_obstacles_node.cpp.

◆ m_subs_2dlaser

std::vector<ros::Subscriber> LocalObstaclesNode::m_subs_2dlaser
private

Subscriber to point cloud sensors.

Definition at line 126 of file mrpt_local_obstacles_node.cpp.

◆ m_subs_pointclouds

std::vector<ros::Subscriber> LocalObstaclesNode::m_subs_pointclouds
private

Definition at line 129 of file mrpt_local_obstacles_node.cpp.

◆ m_tf_buffer

tf2_ros::Buffer LocalObstaclesNode::m_tf_buffer
private

Definition at line 131 of file mrpt_local_obstacles_node.cpp.

◆ m_tf_listener

tf2_ros::TransformListener LocalObstaclesNode::m_tf_listener {m_tf_buffer}
private

Definition at line 132 of file mrpt_local_obstacles_node.cpp.

◆ m_time_window

double LocalObstaclesNode::m_time_window = 0.20
private

[s]can't be smaller than m_publish_period

Definition at line 93 of file mrpt_local_obstacles_node.cpp.

◆ m_timer_publish

ros::Timer LocalObstaclesNode::m_timer_publish
private

Definition at line 96 of file mrpt_local_obstacles_node.cpp.

◆ m_topic_local_map_pointcloud

std::string LocalObstaclesNode::m_topic_local_map_pointcloud = "local_map_pointcloud"
private

Definition at line 88 of file mrpt_local_obstacles_node.cpp.


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


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Mon Aug 14 2023 02:09:04