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)
 
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_frameid_reference
 typ: "odom" More...
 
std::string m_frameid_robot
 typ: "base_link" More...
 
mrpt::gui::CDisplayWindow3D::Ptr m_gui_win
 
TListObservations m_hist_obs
 
boost::mutex m_hist_obs_mtx
 the interest time window. More...
 
CSimplePointsMap m_localmap_pts
 
ros::NodeHandle m_localn
 "~" More...
 
ros::NodeHandle m_nh
 The node handle. More...
 
CTimeLogger m_profiler
 
double m_publish_period
 than m_publish_period More...
 
bool m_show_gui
 
std::string m_source_topics_2dscan
 Default: "scan,laser1". More...
 
double m_time_window
 
ros::Timer m_timer_publish
 than m_time_window More...
 
std::string m_topic_local_map_pointcloud
 Default: "local_map_pointcloud". More...
 
ROS pubs/subs
ros::Publisher m_pub_local_map_pointcloud
 
std::vector< ros::Subscriberm_subs_2dlaser
 Subscriber to 2D laser scans. More...
 
tf::TransformListener m_tf_listener
 Use to retrieve TF data. More...
 

Detailed Description

Definition at line 76 of file mrpt_local_obstacles_node.cpp.

Member Typedef Documentation

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

Definition at line 111 of file mrpt_local_obstacles_node.cpp.

Constructor & Destructor Documentation

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

Constructor: Inits ROS system

Definition at line 382 of file mrpt_local_obstacles_node.cpp.

Member Function Documentation

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

Callback: On recalc local map & publish it

Definition at line 233 of file mrpt_local_obstacles_node.cpp.

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

Callback: On new sensor data

Definition at line 151 of file mrpt_local_obstacles_node.cpp.

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 137 of file mrpt_local_obstacles_node.cpp.

Member Data Documentation

TAuxInitializer LocalObstaclesNode::m_auxinit
private

Just to make sure ROS is init first.

Definition at line 89 of file mrpt_local_obstacles_node.cpp.

std::string LocalObstaclesNode::m_frameid_reference
private

typ: "odom"

Definition at line 93 of file mrpt_local_obstacles_node.cpp.

std::string LocalObstaclesNode::m_frameid_robot
private

typ: "base_link"

Definition at line 94 of file mrpt_local_obstacles_node.cpp.

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

Definition at line 120 of file mrpt_local_obstacles_node.cpp.

TListObservations LocalObstaclesNode::m_hist_obs
private

The history of past observations during

Definition at line 112 of file mrpt_local_obstacles_node.cpp.

boost::mutex LocalObstaclesNode::m_hist_obs_mtx
private

the interest time window.

Definition at line 114 of file mrpt_local_obstacles_node.cpp.

CSimplePointsMap LocalObstaclesNode::m_localmap_pts
private

The local maps

Definition at line 117 of file mrpt_local_obstacles_node.cpp.

ros::NodeHandle LocalObstaclesNode::m_localn
private

"~"

Definition at line 91 of file mrpt_local_obstacles_node.cpp.

ros::NodeHandle LocalObstaclesNode::m_nh
private

The node handle.

Definition at line 90 of file mrpt_local_obstacles_node.cpp.

CTimeLogger LocalObstaclesNode::m_profiler
private

Definition at line 87 of file mrpt_local_obstacles_node.cpp.

ros::Publisher LocalObstaclesNode::m_pub_local_map_pointcloud
private

Definition at line 124 of file mrpt_local_obstacles_node.cpp.

double LocalObstaclesNode::m_publish_period
private

than m_publish_period

In secs (default: 0.05). This can't be larger

Definition at line 100 of file mrpt_local_obstacles_node.cpp.

bool LocalObstaclesNode::m_show_gui
private

Definition at line 92 of file mrpt_local_obstacles_node.cpp.

std::string LocalObstaclesNode::m_source_topics_2dscan
private

Default: "scan,laser1".

Definition at line 97 of file mrpt_local_obstacles_node.cpp.

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

Subscriber to 2D laser scans.

Definition at line 126 of file mrpt_local_obstacles_node.cpp.

tf::TransformListener LocalObstaclesNode::m_tf_listener
private

Use to retrieve TF data.

Definition at line 127 of file mrpt_local_obstacles_node.cpp.

double LocalObstaclesNode::m_time_window
private

In secs (default: 0.2). This can't be smaller

Definition at line 98 of file mrpt_local_obstacles_node.cpp.

ros::Timer LocalObstaclesNode::m_timer_publish
private

than m_time_window

Definition at line 103 of file mrpt_local_obstacles_node.cpp.

std::string LocalObstaclesNode::m_topic_local_map_pointcloud
private

Default: "local_map_pointcloud".

Definition at line 96 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 Thu Mar 12 2020 03:21:40