9 #include <depth_nav_msgs/Point32List.h> 10 #include <geometry_msgs/PointStamped.h> 12 #include <boost/thread.hpp> 21 #include <dynamic_reconfigure/server.h> 22 #include <nav_layer_from_points/NavLayerFromPointsConfig.h> 34 void updateBounds(
double origin_x,
double origin_y,
double origin_z,
35 double* min_x,
double* min_y,
double* max_x,
double* max_y)
override;
38 int min_i,
int min_j,
int max_i,
int max_j)
override;
41 double* max_x,
double* max_y);
54 void configure(NavLayerFromPointsConfig &config, uint32_t level);
76 dynamic_reconfigure::Server<NavLayerFromPointsConfig>*
rec_server_;
77 dynamic_reconfigure::Server<NavLayerFromPointsConfig>::CallbackType
f_;
dynamic_reconfigure::Server< NavLayerFromPointsConfig > * rec_server_
depth_nav_msgs::Point32List points_list_
List of received points.
LayeredCostmap * layered_costmap_
void pointsCallback(const depth_nav_msgs::Point32List &points)
void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) override
ros::Duration points_keep_time_
void configure(NavLayerFromPointsConfig &config, uint32_t level)
tf::TransformListener tf_
void updateBoundsFromPoints(double *min_x, double *min_y, double *max_x, double *max_y)
void onInitialize() override
void updateBounds(double origin_x, double origin_y, double origin_z, double *min_x, double *min_y, double *max_x, double *max_y) override
std::list< geometry_msgs::PointStamped > transformed_points_
boost::recursive_mutex lock_
ros::Subscriber sub_points_
Subscriber for points.
dynamic_reconfigure::Server< NavLayerFromPointsConfig >::CallbackType f_
void clearTransformedPoints()
clearTransformedPoints clears points from list transformed_points_ after some time ...