Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes
LocalObstaclesNode Class Reference

List of all members.

Classes

struct  TAuxInitializer
struct  TInfoPerTimeStep

Public Member Functions

 LocalObstaclesNode (int argc, char **argv)

Private Types

typedef std::multimap< double,
TInfoPerTimeStep
TListObservations

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.

Private Attributes

TAuxInitializer m_auxinit
 Just to make sure ROS is init first.
std::string m_frameid_reference
 typ: "odom"
std::string m_frameid_robot
 typ: "base_link"
mrpt::gui::CDisplayWindow3D::Ptr m_gui_win
TListObservations m_hist_obs
boost::mutex m_hist_obs_mtx
 the interest time window.
CSimplePointsMap m_localmap_pts
ros::NodeHandle m_localn
 "~"
ros::NodeHandle m_nh
 The node handle.
mrpt::utils::CTimeLogger m_profiler
double m_publish_period
 than m_publish_period
bool m_show_gui
std::string m_source_topics_2dscan
 Default: "scan,laser1".
double m_time_window
ros::Timer m_timer_publish
 than m_time_window
std::string m_topic_local_map_pointcloud
 Default: "local_map_pointcloud".
ROS pubs/subs
ros::Publisher m_pub_local_map_pointcloud
std::vector< ros::Subscriberm_subs_2dlaser
 Subscriber to 2D laser scans.
tf::TransformListener m_tf_listener
 Use to retrieve TF data.

Detailed Description

Definition at line 64 of file mrpt_local_obstacles_node.cpp.


Member Typedef Documentation

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

Definition at line 99 of file mrpt_local_obstacles_node.cpp.


Constructor & Destructor Documentation

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

Constructor: Inits ROS system

Definition at line 378 of file mrpt_local_obstacles_node.cpp.


Member Function Documentation

void LocalObstaclesNode::onDoPublish ( const ros::TimerEvent ) [inline, private]

Callback: On recalc local map & publish it

Definition at line 222 of file mrpt_local_obstacles_node.cpp.

void LocalObstaclesNode::onNewSensor_Laser2D ( const sensor_msgs::LaserScanConstPtr &  scan) [inline, private]

Callback: On new sensor data

Definition at line 139 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 
) [inline, private]

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


Member Data Documentation

Just to make sure ROS is init first.

Definition at line 77 of file mrpt_local_obstacles_node.cpp.

typ: "odom"

Definition at line 81 of file mrpt_local_obstacles_node.cpp.

std::string LocalObstaclesNode::m_frameid_robot [private]

typ: "base_link"

Definition at line 82 of file mrpt_local_obstacles_node.cpp.

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

Definition at line 108 of file mrpt_local_obstacles_node.cpp.

The history of past observations during

Definition at line 100 of file mrpt_local_obstacles_node.cpp.

boost::mutex LocalObstaclesNode::m_hist_obs_mtx [private]

the interest time window.

Definition at line 102 of file mrpt_local_obstacles_node.cpp.

CSimplePointsMap LocalObstaclesNode::m_localmap_pts [private]

The local maps

Definition at line 105 of file mrpt_local_obstacles_node.cpp.

"~"

Definition at line 79 of file mrpt_local_obstacles_node.cpp.

The node handle.

Definition at line 78 of file mrpt_local_obstacles_node.cpp.

mrpt::utils::CTimeLogger LocalObstaclesNode::m_profiler [private]

Definition at line 75 of file mrpt_local_obstacles_node.cpp.

Definition at line 112 of file mrpt_local_obstacles_node.cpp.

than m_publish_period

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

Definition at line 88 of file mrpt_local_obstacles_node.cpp.

Definition at line 80 of file mrpt_local_obstacles_node.cpp.

Default: "scan,laser1".

Definition at line 85 of file mrpt_local_obstacles_node.cpp.

Subscriber to 2D laser scans.

Definition at line 114 of file mrpt_local_obstacles_node.cpp.

Use to retrieve TF data.

Definition at line 115 of file mrpt_local_obstacles_node.cpp.

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

Definition at line 86 of file mrpt_local_obstacles_node.cpp.

than m_time_window

Definition at line 91 of file mrpt_local_obstacles_node.cpp.

Default: "local_map_pointcloud".

Definition at line 84 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 Sep 18 2017 03:12:09