Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
nav_layer_from_points::NavLayerFromPoints Class Reference

#include <costmap_layer.h>

Inheritance diagram for nav_layer_from_points::NavLayerFromPoints:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool isDiscretized ()
 NavLayerFromPoints ()
virtual void onInitialize ()
virtual void updateBounds (double origin_x, double origin_y, double origin_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
void updateBoundsFromPoints (double *min_x, double *min_y, double *max_x, double *max_y)
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)

Protected Member Functions

void clearTransformedPoints ()
 clearTransformedPoints clears points from list transformed_points_ after some time
void configure (NavLayerFromPointsConfig &config, uint32_t level)
void pointsCallback (const depth_nav_msgs::Point32List &points)

Protected Attributes

bool first_time_
double last_max_x_
double last_max_y_
double last_min_x_
double last_min_y_
boost::recursive_mutex lock_
ros::Duration points_keep_time_
depth_nav_msgs::Point32List points_list_
 List of received points.
ros::Subscriber sub_points_
 Subscriber for points.
tf::TransformListener tf_
std::list
< geometry_msgs::PointStamped > 
transformed_points_

Private Attributes

dynamic_reconfigure::Server
< NavLayerFromPointsConfig >
::CallbackType 
f_
double point_radius_
dynamic_reconfigure::Server
< NavLayerFromPointsConfig > * 
rec_server_
double robot_radius_

Detailed Description

Definition at line 62 of file costmap_layer.h.


Constructor & Destructor Documentation

Definition at line 65 of file costmap_layer.h.


Member Function Documentation

clearTransformedPoints clears points from list transformed_points_ after some time

Definition at line 83 of file costmap_layer.cpp.

void nav_layer_from_points::NavLayerFromPoints::configure ( NavLayerFromPointsConfig &  config,
uint32_t  level 
) [protected]

Definition at line 66 of file costmap_layer.cpp.

Definition at line 78 of file costmap_layer.h.

Reimplemented from costmap_2d::Layer.

Definition at line 51 of file costmap_layer.cpp.

void nav_layer_from_points::NavLayerFromPoints::pointsCallback ( const depth_nav_msgs::Point32List &  points) [protected]

Definition at line 76 of file costmap_layer.cpp.

void nav_layer_from_points::NavLayerFromPoints::updateBounds ( double  origin_x,
double  origin_y,
double  origin_yaw,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
) [virtual]

Reimplemented from costmap_2d::Layer.

Definition at line 101 of file costmap_layer.cpp.

void nav_layer_from_points::NavLayerFromPoints::updateBoundsFromPoints ( double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)

Definition at line 186 of file costmap_layer.cpp.

void nav_layer_from_points::NavLayerFromPoints::updateCosts ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
) [virtual]

Reimplemented from costmap_2d::Layer.

Definition at line 204 of file costmap_layer.cpp.


Member Data Documentation

dynamic_reconfigure::Server<NavLayerFromPointsConfig>::CallbackType nav_layer_from_points::NavLayerFromPoints::f_ [private]

Definition at line 115 of file costmap_layer.h.

Definition at line 103 of file costmap_layer.h.

Definition at line 104 of file costmap_layer.h.

Definition at line 104 of file costmap_layer.h.

Definition at line 104 of file costmap_layer.h.

Definition at line 104 of file costmap_layer.h.

boost::recursive_mutex nav_layer_from_points::NavLayerFromPoints::lock_ [protected]

Definition at line 102 of file costmap_layer.h.

Definition at line 109 of file costmap_layer.h.

Definition at line 100 of file costmap_layer.h.

depth_nav_msgs::Point32List nav_layer_from_points::NavLayerFromPoints::points_list_ [protected]

List of received points.

Definition at line 93 of file costmap_layer.h.

dynamic_reconfigure::Server<NavLayerFromPointsConfig>* nav_layer_from_points::NavLayerFromPoints::rec_server_ [private]

Definition at line 114 of file costmap_layer.h.

Definition at line 110 of file costmap_layer.h.

Subscriber for points.

Definition at line 92 of file costmap_layer.h.

Reimplemented from costmap_2d::Layer.

Definition at line 95 of file costmap_layer.h.

std::list<geometry_msgs::PointStamped> nav_layer_from_points::NavLayerFromPoints::transformed_points_ [protected]

Definition at line 97 of file costmap_layer.h.


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


nav_layer_from_points
Author(s): Michal Drwiega
autogenerated on Thu Jun 6 2019 22:10:55