4 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) 6 #define OCCUPIED_CELL 100 8 #define UNKNOWN_CELL -1 12 #define ELEVATION_MAP 4 14 #define USE_GRID_MAP_ONLY GRID_MAP 15 #define USE_ELEVATION_MAP_ONLY ELEVATION_MAP 16 #define USE_GRID_AND_ELEVATION_MAP (GRID_MAP | ELEVATION_MAP) 17 #define USE_GRID_AND_CLOUD_MAP (GRID_MAP | CLOUD_MAP) 18 #define USE_GRID_AND_ELEVATION_MAP_AND_CLOUD_MAP (GRID_MAP | CLOUD_MAP | ELEVATION_MAP) 33 cost_map.info.resolution = grid_res_xy;
105 ROS_INFO(
"HectorCM: is up and running.");
115 ROS_INFO(
"HectorCM: Shutting down!");
121 ROS_DEBUG(
"HectorCM: sysMsgCallback, msg contents: %s",
string.data.c_str());
123 if (
string.data ==
"reset")
161 ROS_DEBUG(
"HectorCM: received new map meta data -> overwrite old parameters");
164 if (
cost_map.info.width == map_meta_data.width &&
165 cost_map.info.height == map_meta_data.height &&
166 cost_map.info.resolution == map_meta_data.resolution &&
167 cost_map.info.origin.position.x == map_meta_data.origin.position.x &&
168 cost_map.info.origin.position.y == map_meta_data.origin.position.y &&
169 cost_map.info.origin.position.z == map_meta_data.origin.position.z &&
170 cost_map.info.origin.orientation.x == map_meta_data.origin.orientation.x &&
171 cost_map.info.origin.orientation.y == map_meta_data.origin.orientation.y &&
172 cost_map.info.origin.orientation.z == map_meta_data.origin.orientation.z &&
173 cost_map.info.origin.orientation.w == map_meta_data.origin.orientation.w) {
178 cost_map.info.width = map_meta_data.width;
179 cost_map.info.height = map_meta_data.height;
180 cost_map.info.resolution = map_meta_data.resolution;
182 cost_map.info.origin.position.x = map_meta_data.origin.position.x;
183 cost_map.info.origin.position.y = map_meta_data.origin.position.y;
184 cost_map.info.origin.position.z = map_meta_data.origin.position.z;
186 cost_map.info.origin.orientation.x = map_meta_data.origin.orientation.x;
187 cost_map.info.origin.orientation.y = map_meta_data.origin.orientation.y;
188 cost_map.info.origin.orientation.z = map_meta_data.origin.orientation.z;
189 cost_map.info.origin.orientation.w = map_meta_data.origin.orientation.w;
215 ROS_DEBUG(
"HectorCM: published a new costmap");
227 ROS_DEBUG(
"HectorCM: received new elevation map");
230 if((
int)(1000*elevation_map_msg->info.resolution_xy) != (
int)(1000*
cost_map.info.resolution) &&
231 elevation_map_msg->info.height !=
cost_map.info.height &&
232 elevation_map_msg->info.width !=
cost_map.info.width)
234 ROS_ERROR(
"HectorCM: elevation map resolution and or size incorrect!");
239 elevation_map_ = cv::Mat(elevation_map_msg->info.height, elevation_map_msg->info.width, CV_16S, const_cast<int16_t*>(&elevation_map_msg->data[0]), 2*(
size_t)elevation_map_msg->info.width);
249 int filtered_cell, filtered_cell_x, filtered_cell_y;
269 if(filtered_cell_x > filtered_cell_y)
270 filtered_cell = filtered_cell_x;
272 filtered_cell = filtered_cell_y;
311 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_sensor (
new pcl::PointCloud<pcl::PointXYZ>);
312 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_base_link (
new pcl::PointCloud<pcl::PointXYZ>);
314 ROS_DEBUG(
"HectorCM: received new point cloud");
328 ROS_DEBUG(
"HectorCM: pointcloud transform failed");
336 Eigen::Vector2f world_coords;
338 Eigen::Vector4f minPoint;
340 minPoint[0]=world_coords(0);
341 minPoint[1]=world_coords(1);
344 Eigen::Vector4f maxPoint;
346 maxPoint[0]=world_coords(0);
347 maxPoint[1]=world_coords(1);
350 pcl::CropBox<pcl::PointXYZ> cropFilter;
351 cropFilter.setInputCloud (cloud_base_link);
352 cropFilter.setMin(minPoint);
353 cropFilter.setMax(maxPoint);
364 const pcl::PointXYZ& pt_cloud =
sliced_cloud->points[k];
367 Eigen::Vector2f index_world(pt_cloud.x, pt_cloud.y);
392 ROS_DEBUG(
"HectorCM: received new grid map");
395 if((
int)(1000*grid_map_msg->info.resolution) != (
int)(1000*
cost_map.info.resolution) &&
396 grid_map_msg->info.height !=
cost_map.info.height &&
397 grid_map_msg->info.width !=
cost_map.info.width)
399 ROS_ERROR(
"HectorCM: grid map resolution and or size incorrect!");
448 ROS_DEBUG(
"HectorCM: compute costmap based on grid map");
480 ROS_DEBUG(
"HectorCM: compute costmap based on elevation map");
513 ROS_DEBUG(
"HectorCM: compute costmap based on grid and elevation map");
515 int checksum_grid_map;
529 checksum_grid_map = 0;
531 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u);
532 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u);
533 checksum_grid_map +=
grid_map_.at<int8_t>(v, u-1);
534 checksum_grid_map +=
grid_map_.at<int8_t>(v, u+1);
535 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u+1);
536 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u-1);
537 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u-1);
538 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u+1);
572 ROS_DEBUG(
"HectorCM: compute costmap based on grid and cloud map");
603 ROS_DEBUG(
"HectorCM: compute costmap based on grid, cloud and elevation map");
605 int checksum_grid_map;
619 checksum_grid_map = 0;
621 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u);
622 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u);
623 checksum_grid_map +=
grid_map_.at<int8_t>(v, u-1);
624 checksum_grid_map +=
grid_map_.at<int8_t>(v, u+1);
625 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u+1);
626 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u-1);
627 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u-1);
628 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u+1);
670 ROS_DEBUG(
"HectorCM: computed a new costmap");
679 ROS_WARN(
"Invalid map selection was given to cost map calculation!");
683 if (map_level &
GRID_MAP)
ROS_DEBUG(
"HectorCM: compute costmap based on grid map");
693 int checksum_grid_map = 0;
698 if (map_level & GRID_MAP)
705 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u );
706 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u );
707 checksum_grid_map +=
grid_map_.at<int8_t>(v, u-1);
708 checksum_grid_map +=
grid_map_.at<int8_t>(v, u+1);
709 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u+1);
710 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u-1);
711 checksum_grid_map +=
grid_map_.at<int8_t>(v+1, u-1);
712 checksum_grid_map +=
grid_map_.at<int8_t>(v-1, u+1);
722 if (map_level & CLOUD_MAP)
735 if (map_level & ELEVATION_MAP)
749 ROS_DEBUG(
"HectorCM: computed a new costmap");
756 int update_radius_map;
757 Eigen::Vector2f index_world, index_map;
778 update_radius_map = floor(((
double)update_radius/(
double)
cost_map.info.resolution));
782 if(index_map(1) < update_radius_map)
785 min_index(1) = index_map(1) - update_radius_map;
787 if(index_map(1) + update_radius_map >
cost_map.info.height)
790 max_index(1) = index_map(1) + update_radius_map;
792 if(index_map(0) < update_radius_map)
795 min_index(0) = index_map(0) - update_radius_map;
797 if(index_map(0) + update_radius_map >
cost_map.info.width)
800 max_index(0) = index_map(0) + update_radius_map;
HectorMapTools::CoordinateTransformer< float > world_map_transform
#define USE_GRID_AND_ELEVATION_MAP
void publish(const boost::shared_ptr< M > &message) const
void callbackPointCloud(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
callbackOctoMap get called if a new octo map is available
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
~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
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
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
double max_delta_elevation
ros::Publisher pub_cloud_slice
ROSCPP_DECL void spin(Spinner &spinner)
TFSIMD_FORCE_INLINE const tfScalar & x() const
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
#define USE_GRID_MAP_ONLY
bool calculateCostMap_old(char map_level)
This function fuses the elevation and grid map und calculates the 2d cost map.
tf::TransformListener listener
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool allow_elevation_map_to_clear_occupied_cells
Eigen::Vector2i min_index
TFSIMD_FORCE_INLINE const tfScalar & y() const
void callbackElevationMap(const hector_elevation_msgs::ElevationGridConstPtr &elevation_map_msg)
callbackElevationMap get called if a new elevation map is available
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
bool received_point_cloud
double update_radius_world
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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
#define USE_GRID_AND_CLOUD_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 transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
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_
#define USE_ELEVATION_MAP_ONLY
nav_msgs::OccupancyGrid cloud_cost_map
bool received_elevation_map
#define USE_GRID_AND_ELEVATION_MAP_AND_CLOUD_MAP
double initial_free_cells_radius
std::string sys_msg_topic
#define MAP_IDX(sx, i, j)
ros::Subscriber sub_map_info