#include <hector_elevation_visualization.h>
|
void | visualize_map (const hector_elevation_msgs::ElevationGrid &elevation_map, tf::StampedTransform local_map_transform) |
| visualize_map calculates visualization markers to vizualize the elevation map in rviz More...
|
|
|
static std_msgs::ColorRGBA | heightMapColor (double h) |
| heightMapColor calculates the marker color as a function of height More...
|
|
ElevationVisualization::ElevationVisualization |
( |
| ) |
|
ElevationVisualization::~ElevationVisualization |
( |
| ) |
|
void ElevationVisualization::dynRecParamCallback |
( |
hector_elevation_visualization::ElevationVisualizationConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
dynRecParamCallback This function get called if new parameters has been set with the dynamic reconfigure dialog
- Parameters
-
[in] | config | contains current parameters |
[in] | level | is unused |
Definition at line 43 of file hector_elevation_visualization.cpp.
std_msgs::ColorRGBA ElevationVisualization::heightMapColor |
( |
double |
h | ) |
|
|
staticprivate |
void ElevationVisualization::map_callback |
( |
const hector_elevation_msgs::ElevationGrid & |
elevation_map | ) |
|
map_callback get called if a new elevation map is avaible
- Parameters
-
[in] | elevation_map_msg | stores elevation map data as a 2.5D grid |
Definition at line 124 of file hector_elevation_visualization.cpp.
void ElevationVisualization::sys_message_callback |
( |
const std_msgs::String & |
string | ) |
|
sysMessageCallback This function listen to system messages
- Parameters
-
[in] | string | parameter contains system messages, like "reset" |
Definition at line 162 of file hector_elevation_visualization.cpp.
void ElevationVisualization::visualize_map |
( |
const hector_elevation_msgs::ElevationGrid & |
elevation_map, |
|
|
tf::StampedTransform |
local_map_transform |
|
) |
| |
|
private |
visualize_map calculates visualization markers to vizualize the elevation map in rviz
- Parameters
-
[in] | elevation_map | elevation map data as a 2.5D grid |
[in] | local_map_transform | is used for deducing the robot's position |
Definition at line 60 of file hector_elevation_visualization.cpp.
double ElevationVisualization::color_factor |
|
private |
dynamic_reconfigure::Server<hector_elevation_visualization::ElevationVisualizationConfig> ElevationVisualization::dyn_rec_server_ |
|
private |
std::string ElevationVisualization::elevation_map_frame_id |
|
private |
visualization_msgs::MarkerArray ElevationVisualization::map_marker_array_msg |
|
private |
std_msgs::ColorRGBA ElevationVisualization::marker_color |
|
private |
double ElevationVisualization::max_height |
|
private |
int ElevationVisualization::max_height_levels |
|
private |
double ElevationVisualization::min_height |
|
private |
std::string ElevationVisualization::sys_msg_topic |
|
private |
bool ElevationVisualization::use_color_map |
|
private |
The documentation for this class was generated from the following files: