Public Member Functions | Private Attributes | List of all members
hector_elevation_mapping::ElevationMapping Class Reference

#include <hector_elevation_mapping.h>

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

Public Member Functions

void cloudCallback (const sensor_msgs::PointCloud2ConstPtr &pointcloud2_sensor_msg)
 cloudCallback get called if a new 3D point cloud is avaible More...
 
virtual void onInit ()
 Default plugin constructor. More...
 
void sysMessageCallback (const std_msgs::String &string)
 sysMessageCallback This function listen to system messages More...
 
void timerCallback (const ros::TimerEvent &event)
 timerCallback publishes periodically a height pose update More...
 
void updateParamsCallback (const nav_msgs::MapMetaData &map_meta_data)
 updateMapParamsCallback updates the map meta information if someone has changed it More...
 
 ~ElevationMapping ()
 Default deconstructor. More...
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

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
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Definition at line 26 of file hector_elevation_mapping.h.

Constructor & Destructor Documentation

hector_elevation_mapping::ElevationMapping::~ElevationMapping ( )

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.

void hector_elevation_mapping::ElevationMapping::onInit ( )
virtual

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.

void hector_elevation_mapping::ElevationMapping::timerCallback ( const ros::TimerEvent event)

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

std::vector<double> hector_elevation_mapping::ElevationMapping::cell_variance
private

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.

std::string hector_elevation_mapping::ElevationMapping::global_elevation_map_topic
private

Definition at line 99 of file hector_elevation_mapping.h.

std::string hector_elevation_mapping::ElevationMapping::grid_map_topic
private

Definition at line 99 of file hector_elevation_mapping.h.

tf::TransformListener hector_elevation_mapping::ElevationMapping::listener
private

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.

std::string hector_elevation_mapping::ElevationMapping::local_elevation_map_topic
private

Definition at line 99 of file hector_elevation_mapping.h.

std::string hector_elevation_mapping::ElevationMapping::local_map_frame_id
private

Definition at line 98 of file hector_elevation_mapping.h.

std::string hector_elevation_mapping::ElevationMapping::map_frame_id
private

Definition at line 98 of file hector_elevation_mapping.h.

nav_msgs::MapMetaData hector_elevation_mapping::ElevationMapping::map_meta
private

Definition at line 86 of file hector_elevation_mapping.h.

int hector_elevation_mapping::ElevationMapping::max_height
private

Definition at line 92 of file hector_elevation_mapping.h.

int hector_elevation_mapping::ElevationMapping::max_height_levels
private

Definition at line 92 of file hector_elevation_mapping.h.

double hector_elevation_mapping::ElevationMapping::max_observable_distance
private

Definition at line 89 of file hector_elevation_mapping.h.

ros::NodeHandle hector_elevation_mapping::ElevationMapping::nHandle
private

Definition at line 65 of file hector_elevation_mapping.h.

ros::NodeHandle hector_elevation_mapping::ElevationMapping::nPrivateHandle
private

Definition at line 66 of file hector_elevation_mapping.h.

std::string hector_elevation_mapping::ElevationMapping::point_cloud_topic
private

Definition at line 99 of file hector_elevation_mapping.h.

std::string hector_elevation_mapping::ElevationMapping::pose_update_topic
private

Definition at line 99 of file hector_elevation_mapping.h.

double hector_elevation_mapping::ElevationMapping::poseupdate_height_covariance
private

Definition at line 95 of file hector_elevation_mapping.h.

double hector_elevation_mapping::ElevationMapping::poseupdate_pub_period
private

Definition at line 94 of file hector_elevation_mapping.h.

int hector_elevation_mapping::ElevationMapping::poseupdate_used_pattern_size
private

Definition at line 96 of file hector_elevation_mapping.h.

ros::Publisher hector_elevation_mapping::ElevationMapping::pub_global_map
private

Definition at line 74 of file hector_elevation_mapping.h.

ros::Publisher hector_elevation_mapping::ElevationMapping::pub_global_map_meta
private

Definition at line 75 of file hector_elevation_mapping.h.

ros::Publisher hector_elevation_mapping::ElevationMapping::pub_height_update
private

Definition at line 77 of file hector_elevation_mapping.h.

ros::Publisher hector_elevation_mapping::ElevationMapping::pub_local_map
private

Definition at line 72 of file hector_elevation_mapping.h.

ros::Publisher hector_elevation_mapping::ElevationMapping::pub_local_map_meta
private

Definition at line 73 of file hector_elevation_mapping.h.

bool hector_elevation_mapping::ElevationMapping::publish_poseupdate
private

Definition at line 91 of file hector_elevation_mapping.h.

std::string hector_elevation_mapping::ElevationMapping::sensor_frame_id
private

Definition at line 98 of file hector_elevation_mapping.h.

double hector_elevation_mapping::ElevationMapping::sensor_variance
private

Definition at line 88 of file hector_elevation_mapping.h.

ros::Subscriber hector_elevation_mapping::ElevationMapping::sub_grid_map_info
private

Definition at line 70 of file hector_elevation_mapping.h.

ros::Subscriber hector_elevation_mapping::ElevationMapping::sub_pointCloud
private

Definition at line 68 of file hector_elevation_mapping.h.

ros::Subscriber hector_elevation_mapping::ElevationMapping::sub_sysMessage
private

Definition at line 69 of file hector_elevation_mapping.h.

std::string hector_elevation_mapping::ElevationMapping::sys_msg_topic
private

Definition at line 99 of file hector_elevation_mapping.h.

ros::Timer hector_elevation_mapping::ElevationMapping::timer
private

Definition at line 79 of file hector_elevation_mapping.h.

HectorMapTools::CoordinateTransformer<float> hector_elevation_mapping::ElevationMapping::world_map_transform
private

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 Mon Jun 10 2019 13:34:35