6 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) 14 int width, height, zero_elevation;
16 nPrivateHandle = getPrivateNodeHandle();
17 nHandle = getNodeHandle();
19 nPrivateHandle.param(
"elevation_resolution", elevation_map_meta.resolution_z, 0.01);
20 nPrivateHandle.param(
"elevation_zero_level", zero_elevation, 16384);
21 elevation_map_meta.zero_elevation = zero_elevation;
22 nPrivateHandle.param(
"min_observable_elevation", elevation_map_meta.min_elevation, -1.00);
23 nPrivateHandle.param(
"max_observable_elevation", elevation_map_meta.max_elevation, 0.30);
24 nPrivateHandle.param(
"max_observable_distance", max_observable_distance, 4.00);
26 nPrivateHandle.param(
"map_resolution", elevation_map_meta.resolution_xy, 0.05);
27 nPrivateHandle.param(
"max_grid_size_x", width, 1024);
28 elevation_map_meta.width = width;
29 nPrivateHandle.param(
"max_grid_size_y", height, 1024);
30 elevation_map_meta.height = height;
32 nPrivateHandle.param(
"publish_poseupdate", publish_poseupdate,
true);
34 nPrivateHandle.param(
"sensor_variance", sensor_variance, 0.001);
36 nPrivateHandle.param(
"origin_x",elevation_map_meta.origin.position.x, -(
double)elevation_map_meta.width*(
double)elevation_map_meta.resolution_xy/2.0f);
37 nPrivateHandle.param(
"origin_y",elevation_map_meta.origin.position.y, -(
double)elevation_map_meta.height*(
double)elevation_map_meta.resolution_xy/2.0f);
38 nPrivateHandle.param(
"origin_z",elevation_map_meta.origin.position.z, 0.0);
39 nPrivateHandle.param(
"orientation_x",elevation_map_meta.origin.orientation.x, 0.0);
40 nPrivateHandle.param(
"orientation_y",elevation_map_meta.origin.orientation.y, 0.0);
41 nPrivateHandle.param(
"orientation_z",elevation_map_meta.origin.orientation.z, 0.0);
42 nPrivateHandle.param(
"orientation_w",elevation_map_meta.origin.orientation.w, 1.0);
44 local_elevation_map.info = elevation_map_meta;
45 global_elevation_map.info = elevation_map_meta;
47 map_meta.origin.position.x = elevation_map_meta.origin.position.x;
48 map_meta.origin.position.y = elevation_map_meta.origin.position.y;
49 map_meta.origin.position.z = elevation_map_meta.origin.position.z;
51 map_meta.origin.orientation.x = elevation_map_meta.origin.orientation.x;
52 map_meta.origin.orientation.y = elevation_map_meta.origin.orientation.y;
53 map_meta.origin.orientation.z = elevation_map_meta.origin.orientation.z;
54 map_meta.origin.orientation.w = elevation_map_meta.origin.orientation.w;
56 map_meta.resolution = elevation_map_meta.resolution_xy;
57 world_map_transform.setTransforms(map_meta);
59 nPrivateHandle.param(
"map_frame_id", map_frame_id,std::string(
"map"));
60 nPrivateHandle.param(
"local_map_frame_id", local_map_frame_id,std::string(
"base_stabilized"));
61 nPrivateHandle.param(
"local_elevation_map_topic", local_elevation_map_topic, std::string(
"elevation_map_local"));
62 nPrivateHandle.param(
"global_elevation_map_topic", global_elevation_map_topic, std::string(
"elevation_map_global"));
63 nPrivateHandle.param(
"point_cloud_topic", point_cloud_topic, std::string(
"openni/depth/points"));
64 nPrivateHandle.param(
"grid_map_topic", grid_map_topic, std::string(
"scanmatcher_map"));
65 nPrivateHandle.param(
"pose_update_topic",pose_update_topic,std::string(
"poseupdate"));
67 nPrivateHandle.param(
"sys_msg_topic", sys_msg_topic, std::string(
"syscommand"));
69 nPrivateHandle.param(
"poseupdate_pub_period",poseupdate_pub_period,1.0);
70 nPrivateHandle.param(
"poseupdate_height_covariance",poseupdate_height_covariance,0.25);
71 nPrivateHandle.param(
"poseupdate_used_pattern_size",poseupdate_used_pattern_size,3);
74 local_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
75 global_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
76 cell_variance = std::vector<double>(elevation_map_meta.width * elevation_map_meta.height,std::numeric_limits<double>::max());
82 pub_local_map = nPrivateHandle.advertise<hector_elevation_msgs::ElevationGrid>(local_elevation_map_topic, 1,
true);
83 pub_local_map_meta = nPrivateHandle.advertise<hector_elevation_msgs::ElevationMapMetaData>(local_elevation_map_topic +
"_metadata", 1,
true);
84 pub_global_map = nPrivateHandle.advertise<hector_elevation_msgs::ElevationGrid>(global_elevation_map_topic, 1,
true);
85 pub_global_map_meta = nPrivateHandle.advertise<hector_elevation_msgs::ElevationMapMetaData>(global_elevation_map_topic +
"_metadata", 1,
true);
87 pub_local_map_meta.publish(local_elevation_map.info);
88 pub_global_map_meta.publish(global_elevation_map.info);
90 pub_height_update = nPrivateHandle.advertise<geometry_msgs::PoseWithCovarianceStamped>(pose_update_topic, 1,
true);
92 if(publish_poseupdate)
95 ROS_INFO(
"HectorEM: is up and running.");
100 ROS_INFO(
"HectorEM: Shutting down!");
115 ROS_DEBUG(
"HectorEM: localmap transform in timer callback failed");
121 Eigen::Vector2f index_world(local_map_transform.
getOrigin().
x(), local_map_transform.
getOrigin().
y());
127 geometry_msgs::PoseWithCovarianceStamped cell_height_average;
154 if(error_level < pattern_cell_quantity/2)
156 pattern_cell_quantity -= error_level;
158 cell_height_average.pose.pose.position.z = cell_height_average.pose.pose.position.z/(double)pattern_cell_quantity;
163 cell_height_average.pose.covariance.at(0) = 0.0;
164 cell_height_average.pose.covariance.at(7) = 0.0;
169 ROS_DEBUG(
"HectorEM: published height update %f",cell_height_average.pose.pose.position.z);
177 ROS_DEBUG(
"HectorEM: sysMsgCallback, msg contents: %s",
string.data.c_str());
179 if (
string.data ==
"reset")
193 ROS_DEBUG(
"HectorEM: received new grid map meta data -> overwrite old parameters");
226 pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud2_map_pcl (
new pcl::PointCloud<pcl::PointXYZ> ()),
227 pointcloud2_sensor_pcl (
new pcl::PointCloud<pcl::PointXYZ> ());
230 ROS_DEBUG(
"HectorEM received a point cloud.");
245 ROS_DEBUG(
"HectorEM: pointcloud transform failed");
258 ROS_DEBUG(
"HectorEM: localmap transform in cloud callback failed");
265 if(local_map_is_subscribed)
268 unsigned int size = (
unsigned int)pointcloud2_map_pcl->points.size();
271 for (
unsigned int k = 0; k < size; ++k)
273 const pcl::PointXYZ& pt_cloud = pointcloud2_map_pcl->points[k];
275 double measurement_distance = pointcloud2_sensor_pcl->points[k].z;
278 if (isnan(pt_cloud.x) || isnan(pt_cloud.y) || isnan(pt_cloud.z))
290 Eigen::Vector2f index_world(pt_cloud.x, pt_cloud.y);
300 if(local_map_is_subscribed)
306 if(pt_cloud.z > cell_elevation)
333 double measurement_variance =
sensor_variance*(measurement_distance*measurement_distance);
336 double mahalanobis_distance = sqrt((pt_cloud.z - cell_elevation)*(pt_cloud.z - cell_elevation)/(measurement_variance*measurement_variance));
338 if(pt_cloud.z > cell_elevation && (mahalanobis_distance > 5.0))
341 *pt_var = measurement_variance;
345 if((pt_cloud.z < cell_elevation) && (mahalanobis_distance > 5.0))
347 *pt_global_map = (int16_t) (round(((measurement_variance * cell_elevation + *pt_var * pt_cloud.z)/(*pt_var + measurement_variance))/
elevation_map_meta.resolution_z) + (int16_t)
elevation_map_meta.zero_elevation);
349 *pt_var = measurement_variance;
353 *pt_global_map = (int16_t) (round(((measurement_variance * cell_elevation + *pt_var * pt_cloud.z)/(*pt_var + measurement_variance))/
elevation_map_meta.resolution_z) + (int16_t)
elevation_map_meta.zero_elevation);
354 *pt_var = (measurement_variance * *pt_var)/(measurement_variance + *pt_var);
359 if(local_map_is_subscribed)
368 if(global_map_is_subscribed)
void publish(const boost::shared_ptr< M > &message) const
tf::TransformListener listener
#define MAP_IDX(sx, i, j)
ros::Publisher pub_global_map_meta
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
hector_elevation_msgs::ElevationGrid global_elevation_map
void updateParamsCallback(const nav_msgs::MapMetaData &map_meta_data)
updateMapParamsCallback updates the map meta information if someone has changed it ...
HectorMapTools::CoordinateTransformer< float > world_map_transform
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
hector_elevation_msgs::ElevationGrid local_elevation_map
TFSIMD_FORCE_INLINE const tfScalar & y() const
void timerCallback(const ros::TimerEvent &event)
timerCallback publishes periodically a height pose update
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
std::string local_map_frame_id
void sysMessageCallback(const std_msgs::String &string)
sysMessageCallback This function listen to system messages
nav_msgs::MapMetaData map_meta
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
void cloudCallback(const sensor_msgs::PointCloud2ConstPtr &pointcloud2_sensor_msg)
cloudCallback get called if a new 3D point cloud is avaible
std::vector< double > cell_variance
double max_observable_distance
uint32_t getNumSubscribers() const
ros::Publisher pub_global_map
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
int poseupdate_used_pattern_size
ros::Publisher pub_local_map_meta
ros::Publisher pub_local_map
double poseupdate_height_covariance
ros::Publisher pub_height_update
hector_elevation_msgs::ElevationMapMetaData elevation_map_meta
~ElevationMapping()
Default deconstructor.