2 #include "pcl/point_types.h" 8 #include <std_msgs/String.h> 11 #include <hector_elevation_msgs/ElevationMapMetaData.h> 12 #include <hector_elevation_msgs/ElevationGrid.h> 14 #include <nav_msgs/OccupancyGrid.h> 15 #include <nav_msgs/MapMetaData.h> 19 #include <geometry_msgs/PoseWithCovarianceStamped.h> 39 void cloudCallback(
const sensor_msgs::PointCloud2ConstPtr& pointcloud2_sensor_msg);
virtual void onInit()
Default plugin constructor.
tf::TransformListener listener
ros::Publisher pub_global_map_meta
std::string pose_update_topic
ros::Subscriber sub_sysMessage
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
ros::Subscriber sub_grid_map_info
hector_elevation_msgs::ElevationGrid local_elevation_map
void timerCallback(const ros::TimerEvent &event)
timerCallback publishes periodically a height pose update
double poseupdate_pub_period
std::string point_cloud_topic
std::string sys_msg_topic
std::string sensor_frame_id
std::string local_map_frame_id
void sysMessageCallback(const std_msgs::String &string)
sysMessageCallback This function listen to system messages
std::string local_elevation_map_topic
nav_msgs::MapMetaData map_meta
void cloudCallback(const sensor_msgs::PointCloud2ConstPtr &pointcloud2_sensor_msg)
cloudCallback get called if a new 3D point cloud is avaible
ros::NodeHandle nPrivateHandle
std::vector< double > cell_variance
double max_observable_distance
ros::Publisher pub_global_map
int poseupdate_used_pattern_size
std::string global_elevation_map_topic
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
std::string grid_map_topic
ros::Subscriber sub_pointCloud
~ElevationMapping()
Default deconstructor.