◆ TListObservations
◆ LocalObstaclesNode()
LocalObstaclesNode::LocalObstaclesNode |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
|
inline |
◆ onDoPublish()
◆ onNewSensor_Laser2D()
void LocalObstaclesNode::onNewSensor_Laser2D |
( |
const sensor_msgs::LaserScanConstPtr & |
scan | ) |
|
|
inlineprivate |
◆ onNewSensor_PointCloud()
void LocalObstaclesNode::onNewSensor_PointCloud |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
pts | ) |
|
|
inlineprivate |
◆ 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
-
lstTopics | String 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.
◆ m_auxinit
◆ m_filter_output_layer_name
std::string LocalObstaclesNode::m_filter_output_layer_name |
|
private |
◆ m_filter_pipeline
◆ m_frameid_reference
std::string LocalObstaclesNode::m_frameid_reference = "odom" |
|
private |
◆ m_frameid_robot
std::string LocalObstaclesNode::m_frameid_robot = "base_link" |
|
private |
◆ m_gui_win
mrpt::gui::CDisplayWindow3D::Ptr LocalObstaclesNode::m_gui_win |
|
private |
◆ m_hist_obs
◆ m_hist_obs_mtx
boost::mutex LocalObstaclesNode::m_hist_obs_mtx |
|
private |
◆ m_localmap_pts
CSimplePointsMap::Ptr LocalObstaclesNode::m_localmap_pts = CSimplePointsMap::Create() |
|
private |
◆ m_localn
◆ m_nh
◆ m_profiler
CTimeLogger LocalObstaclesNode::m_profiler |
|
private |
◆ m_pub_local_map_pointcloud
◆ m_publish_period
double LocalObstaclesNode::m_publish_period = 0.05 |
|
private |
◆ m_show_gui
bool LocalObstaclesNode::m_show_gui = true |
|
private |
◆ m_source_topics_2dscan
std::string LocalObstaclesNode::m_source_topics_2dscan = "scan,laser1" |
|
private |
◆ m_source_topics_pointclouds
std::string LocalObstaclesNode::m_source_topics_pointclouds = "" |
|
private |
◆ m_subs_2dlaser
◆ m_subs_pointclouds
◆ m_tf_buffer
◆ m_tf_listener
◆ m_time_window
double LocalObstaclesNode::m_time_window = 0.20 |
|
private |
◆ m_timer_publish
◆ m_topic_local_map_pointcloud
std::string LocalObstaclesNode::m_topic_local_map_pointcloud = "local_map_pointcloud" |
|
private |
The documentation for this class was generated from the following file: