Public Member Functions | Private Attributes
hector_elevation_mapping::ElevationMapping Class Reference

#include <hector_elevation_mapping.h>

Inheritance diagram for hector_elevation_mapping::ElevationMapping:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void cloudCallback (const sensor_msgs::PointCloud2ConstPtr &pointcloud2_sensor_msg)
 cloudCallback get called if a new 3D point cloud is avaible
virtual void onInit ()
 Default plugin constructor.
void sysMessageCallback (const std_msgs::String &string)
 sysMessageCallback This function listen to system messages
void timerCallback (const ros::TimerEvent &event)
 timerCallback publishes periodically a height pose update
void updateParamsCallback (const nav_msgs::MapMetaData &map_meta_data)
 updateMapParamsCallback updates the map meta information if someone has changed it
 ~ElevationMapping ()
 Default deconstructor.

Private Attributes

std::vector< double > cell_variance
hector_elevation_msgs::ElevationMapMetaData elevation_map_meta
hector_elevation_msgs::ElevationGrid global_elevation_map
std::string global_elevation_map_topic
std::string grid_map_topic
tf::TransformListener listener
hector_elevation_msgs::ElevationGrid local_elevation_map
std::string local_elevation_map_topic
std::string local_map_frame_id
std::string map_frame_id
nav_msgs::MapMetaData map_meta
int max_height
int max_height_levels
double max_observable_distance
ros::NodeHandle nHandle
ros::NodeHandle nPrivateHandle
std::string point_cloud_topic
std::string pose_update_topic
double poseupdate_height_covariance
double poseupdate_pub_period
int poseupdate_used_pattern_size
ros::Publisher pub_global_map
ros::Publisher pub_global_map_meta
ros::Publisher pub_height_update
ros::Publisher pub_local_map
ros::Publisher pub_local_map_meta
bool publish_poseupdate
std::string sensor_frame_id
double sensor_variance
ros::Subscriber sub_grid_map_info
ros::Subscriber sub_pointCloud
ros::Subscriber sub_sysMessage
std::string sys_msg_topic
ros::Timer timer
HectorMapTools::CoordinateTransformer
< float > 
world_map_transform

Detailed Description

Definition at line 26 of file hector_elevation_mapping.h.


Constructor & Destructor Documentation

Default deconstructor.

Definition at line 98 of file hector_elevation_mapping.cpp.


Member Function Documentation

void hector_elevation_mapping::ElevationMapping::cloudCallback ( const sensor_msgs::PointCloud2ConstPtr &  pointcloud2_sensor_msg)

cloudCallback get called if a new 3D point cloud is avaible

Parameters:
[in]pointcloud2_sensor_msgcontains the 3D point cloud

Definition at line 224 of file hector_elevation_mapping.cpp.

Default plugin constructor.

Implements nodelet::Nodelet.

Definition at line 12 of file hector_elevation_mapping.cpp.

void hector_elevation_mapping::ElevationMapping::sysMessageCallback ( const std_msgs::String &  string)

sysMessageCallback This function listen to system messages

Parameters:
[in]stringparameter contains system messages, like "reset"

Definition at line 175 of file hector_elevation_mapping.cpp.

timerCallback publishes periodically a height pose update

Parameters:
[in]eventis not used

todo check if min/max index is inside map

Definition at line 103 of file hector_elevation_mapping.cpp.

void hector_elevation_mapping::ElevationMapping::updateParamsCallback ( const nav_msgs::MapMetaData &  map_meta_data)

updateMapParamsCallback updates the map meta information if someone has changed it

Parameters:
[in]map_meta_datamap meta information like grid resolution or origin

Definition at line 191 of file hector_elevation_mapping.cpp.


Member Data Documentation

Definition at line 84 of file hector_elevation_mapping.h.

hector_elevation_msgs::ElevationMapMetaData hector_elevation_mapping::ElevationMapping::elevation_map_meta [private]

Definition at line 81 of file hector_elevation_mapping.h.

hector_elevation_msgs::ElevationGrid hector_elevation_mapping::ElevationMapping::global_elevation_map [private]

Definition at line 83 of file hector_elevation_mapping.h.

Definition at line 99 of file hector_elevation_mapping.h.

Definition at line 99 of file hector_elevation_mapping.h.

Definition at line 64 of file hector_elevation_mapping.h.

hector_elevation_msgs::ElevationGrid hector_elevation_mapping::ElevationMapping::local_elevation_map [private]

Definition at line 82 of file hector_elevation_mapping.h.

Definition at line 99 of file hector_elevation_mapping.h.

Definition at line 98 of file hector_elevation_mapping.h.

Definition at line 98 of file hector_elevation_mapping.h.

Definition at line 86 of file hector_elevation_mapping.h.

Definition at line 92 of file hector_elevation_mapping.h.

Definition at line 92 of file hector_elevation_mapping.h.

Definition at line 89 of file hector_elevation_mapping.h.

Definition at line 65 of file hector_elevation_mapping.h.

Definition at line 66 of file hector_elevation_mapping.h.

Definition at line 99 of file hector_elevation_mapping.h.

Definition at line 99 of file hector_elevation_mapping.h.

Definition at line 95 of file hector_elevation_mapping.h.

Definition at line 94 of file hector_elevation_mapping.h.

Definition at line 96 of file hector_elevation_mapping.h.

Definition at line 74 of file hector_elevation_mapping.h.

Definition at line 75 of file hector_elevation_mapping.h.

Definition at line 77 of file hector_elevation_mapping.h.

Definition at line 72 of file hector_elevation_mapping.h.

Definition at line 73 of file hector_elevation_mapping.h.

Definition at line 91 of file hector_elevation_mapping.h.

Definition at line 98 of file hector_elevation_mapping.h.

Definition at line 88 of file hector_elevation_mapping.h.

Definition at line 70 of file hector_elevation_mapping.h.

Definition at line 68 of file hector_elevation_mapping.h.

Definition at line 69 of file hector_elevation_mapping.h.

Definition at line 99 of file hector_elevation_mapping.h.

Definition at line 79 of file hector_elevation_mapping.h.

Definition at line 62 of file hector_elevation_mapping.h.


The documentation for this class was generated from the following files:


hector_elevation_mapping
Author(s):
autogenerated on Wed Sep 6 2017 02:41:26