1 #include <hector_elevation_msgs/ElevationMapMetaData.h> 2 #include <hector_elevation_msgs/ElevationGrid.h> 4 #include <std_msgs/String.h> 5 #include <nav_msgs/OccupancyGrid.h> 6 #include <nav_msgs/MapMetaData.h> 10 #include <opencv/cv.h> 11 #include <opencv/highgui.h> 15 #include <pcl/point_types.h> 16 #include <pcl/filters/crop_box.h> 24 #include <dynamic_reconfigure/server.h> 25 #include <hector_costmap/CostMapCalculationConfig.h> 46 void callbackElevationMap(
const hector_elevation_msgs::ElevationGridConstPtr& elevation_map_msg);
58 void callbackGridMap(
const nav_msgs::OccupancyGridConstPtr& grid_map_msg);
92 dynamic_reconfigure::Server<hector_costmap::CostMapCalculationConfig>
dyn_rec_server_;
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
~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
cv::Mat elevation_cost_map_
double max_delta_elevation
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
bool received_point_cloud
double update_radius_world
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::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
bool received_elevation_map
double initial_free_cells_radius
std::string sys_msg_topic
ros::Subscriber sub_map_info