hector_costmap.h
Go to the documentation of this file.
1 #include <hector_elevation_msgs/ElevationMapMetaData.h>
2 #include <hector_elevation_msgs/ElevationGrid.h>
3 
4 #include <std_msgs/String.h>
5 #include <nav_msgs/OccupancyGrid.h>
6 #include <nav_msgs/MapMetaData.h>
7 
8 #include <ros/ros.h>
9 
10 #include <opencv/cv.h>
11 #include <opencv/highgui.h>
12 
13 #include <cv_bridge/cv_bridge.h>
14 
15 #include <pcl/point_types.h>
16 #include <pcl/filters/crop_box.h>
17 #include <pcl_ros/point_cloud.h>
18 #include <pcl_ros/transforms.h>
19 
21 
22 #include <tf/transform_listener.h>
23 
24 #include <dynamic_reconfigure/server.h>
25 #include <hector_costmap/CostMapCalculationConfig.h>
26 
28 
29 public:
32 
35 
37 
40  void updateMapParamsCallback(const nav_msgs::MapMetaData& map_meta_data);
41 
43 
46  void callbackElevationMap(const hector_elevation_msgs::ElevationGridConstPtr& elevation_map_msg);
47 
49 
52  void callbackPointCloud(const sensor_msgs::PointCloud2ConstPtr &cloud_msg);
53 
55 
58  void callbackGridMap(const nav_msgs::OccupancyGridConstPtr& grid_map_msg);
59 
61 
64  void sysMessageCallback(const std_msgs::String& string);
65 
67 
71  void dynRecParamCallback(hector_costmap::CostMapCalculationConfig &config, uint32_t level);
72 
74 
77  void timerCallback(const ros::TimerEvent& event);
78 
79 private:
82 
85 
91 
92  dynamic_reconfigure::Server<hector_costmap::CostMapCalculationConfig> dyn_rec_server_;
93 
95 
97 
99 
101  double grid_res_z;
108 
109  pcl::PointCloud<pcl::PointXYZ>::Ptr sliced_cloud;
110  nav_msgs::OccupancyGridConstPtr grid_map_msg_;
111 
112  nav_msgs::OccupancyGrid cost_map, elevation_cost_map, cloud_cost_map;
113 
115 
118 
119  Eigen::Vector2i min_index, max_index;
120 
122 
126  bool calculateCostMap_old(char map_level);
127 
129 
133  bool calculateCostMap(char map_level);
134 
136 
141  bool computeWindowIndices(ros::Time time,double update_radius);
142 };
143 
HectorMapTools::CoordinateTransformer< float > world_map_transform
cv::Mat elevation_map_filtered
void callbackPointCloud(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
callbackOctoMap get called if a new octo map is available
std::string map_frame_id
~CostMapCalculation()
Default deconstructor.
ros::Subscriber sub_point_cloud
void sysMessageCallback(const std_msgs::String &string)
sysMessageCallback This function listen to system messages
bool calculateCostMap(char map_level)
This function fuses the elevation and grid map und calculates the 2d cost map.
std::string point_cloud_topic
CostMapCalculation()
Default constructor.
void callbackGridMap(const nav_msgs::OccupancyGridConstPtr &grid_map_msg)
callbackGridMap get called if a new 2D grid map is available
std::string grid_map_topic
ros::Publisher pub_cloud_slice
ros::Subscriber sub_elevation_map
std::string local_transform_frame_id
bool computeWindowIndices(ros::Time time, double update_radius)
Computes the indices for the bounding box thats get updated.
ros::Subscriber sub_grid_map
bool calculateCostMap_old(char map_level)
This function fuses the elevation and grid map und calculates the 2d cost map.
tf::TransformListener listener
bool allow_elevation_map_to_clear_occupied_cells
Eigen::Vector2i min_index
void callbackElevationMap(const hector_elevation_msgs::ElevationGridConstPtr &elevation_map_msg)
callbackElevationMap get called if a new elevation map is available
void dynRecParamCallback(hector_costmap::CostMapCalculationConfig &config, uint32_t level)
dynRecParamCallback This function get called if new parameters has been set with the dynamic reconfig...
nav_msgs::OccupancyGrid elevation_cost_map
ros::NodeHandle pnHandle
ros::Subscriber sub_sysMessage
std::string cost_map_topic
pcl::PointCloud< pcl::PointXYZ >::Ptr sliced_cloud
ros::Publisher pub_cost_map
nav_msgs::OccupancyGrid cost_map
void timerCallback(const ros::TimerEvent &event)
timerCallback publishes periodically a new 2D cost map
std::string elevation_map_topic
void updateMapParamsCallback(const nav_msgs::MapMetaData &map_meta_data)
updateMapParamsCallback updates the map meta information if someone has changed it ...
dynamic_reconfigure::Server< hector_costmap::CostMapCalculationConfig > dyn_rec_server_
Eigen::Vector2i max_index
nav_msgs::OccupancyGridConstPtr grid_map_msg_
nav_msgs::OccupancyGrid cloud_cost_map
double initial_free_cells_radius
std::string sys_msg_topic
ros::NodeHandle nHandle
ros::Subscriber sub_map_info


hector_costmap
Author(s):
autogenerated on Mon Jun 10 2019 13:34:32