costmap_layer.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
5 #include <costmap_2d/footprint.h>
6 #include <costmap_2d/layer.h>
8 
9 #include <depth_nav_msgs/Point32List.h>
10 #include <geometry_msgs/PointStamped.h>
11 
12 #include <boost/thread.hpp>
13 
14 #include <tf/transform_listener.h>
15 
16 #include <math.h>
17 #include <algorithm>
18 
19 #include <angles/angles.h>
20 
21 #include <dynamic_reconfigure/server.h>
22 #include <nav_layer_from_points/NavLayerFromPointsConfig.h>
23 
24 
26 {
28 {
29 public:
31 
32  void onInitialize() override;
33 
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;
36 
37  void updateCosts(costmap_2d::Costmap2D& master_grid,
38  int min_i, int min_j, int max_i, int max_j) override;
39 
40  void updateBoundsFromPoints( double* min_x, double* min_y,
41  double* max_x, double* max_y);
42 
43  bool isDiscretized() { return false; }
44 
45 protected:
46 
47  void pointsCallback(const depth_nav_msgs::Point32List& points);
48 
53 
54  void configure(NavLayerFromPointsConfig &config, uint32_t level);
55 
56 protected: // Protected fields
58  depth_nav_msgs::Point32List points_list_;
59 
61 
62  std::list<geometry_msgs::PointStamped> transformed_points_;
63 
64  // After this time points will be delete
66 
67  boost::recursive_mutex lock_;
70 
71 private:
72  // ROS parameters configurated with config file or dynamic_reconfigure
73  double point_radius_;
74  double robot_radius_;
75 
76  dynamic_reconfigure::Server<NavLayerFromPointsConfig>* rec_server_;
77  dynamic_reconfigure::Server<NavLayerFromPointsConfig>::CallbackType f_;
78 };
79 
80 } // namespace nav_layer_from_points
dynamic_reconfigure::Server< NavLayerFromPointsConfig > * rec_server_
Definition: costmap_layer.h:76
depth_nav_msgs::Point32List points_list_
List of received points.
Definition: costmap_layer.h:58
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
void configure(NavLayerFromPointsConfig &config, uint32_t level)
void updateBoundsFromPoints(double *min_x, double *min_y, double *max_x, double *max_y)
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_
Definition: costmap_layer.h:62
ros::Subscriber sub_points_
Subscriber for points.
Definition: costmap_layer.h:57
dynamic_reconfigure::Server< NavLayerFromPointsConfig >::CallbackType f_
Definition: costmap_layer.h:77
void clearTransformedPoints()
clearTransformedPoints clears points from list transformed_points_ after some time ...


nav_layer_from_points
Author(s): Michal Drwiega (http://www.mdrwiega.com)
autogenerated on Wed May 5 2021 02:56:19