#include <VectorVisualization.hpp>

Public Member Functions | |
| bool | initialize () |
| bool | readParameters (XmlRpc::XmlRpcValue &config) |
| VectorVisualization (ros::NodeHandle &nodeHandle, const std::string &name) | |
| bool | visualize (const grid_map::GridMap &map) |
| virtual | ~VectorVisualization () |
Public Member Functions inherited from grid_map_visualization::VisualizationBase | |
| bool | isActive () const |
| VisualizationBase (ros::NodeHandle &nodeHandle, const std::string &name) | |
| virtual | ~VisualizationBase () |
Private Attributes | |
| std_msgs::ColorRGBA | color_ |
| Color of the vectors. More... | |
| double | lineWidth_ |
| Width of the line markers [m]. More... | |
| visualization_msgs::Marker | marker_ |
| Marker to be published. More... | |
| std::string | positionLayer_ |
| Type that is the position of the vectors. More... | |
| double | scale_ |
| Scaling of the vectors. More... | |
| std::vector< std::string > | types_ |
| Types that are transformed to vectors. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from grid_map_visualization::VisualizationBase | |
| bool | getParam (const std::string &name, std::string &value) |
| bool | getParam (const std::string &name, double &value) |
| bool | getParam (const std::string &name, float &value) |
| bool | getParam (const std::string &name, int &value) |
| bool | getParam (const std::string &name, bool &value) |
Protected Attributes inherited from grid_map_visualization::VisualizationBase | |
| std::string | name_ |
| Name of the visualization. More... | |
| ros::NodeHandle & | nodeHandle_ |
| ROS nodehandle. More... | |
| StringMap | parameters_ |
| Storage of the parsed XML parameters. More... | |
| ros::Publisher | publisher_ |
| ROS publisher of the occupancy grid. More... | |
Visualization a combination of three layers of the grid map as a vector field.
Definition at line 27 of file VectorVisualization.hpp.
| grid_map_visualization::VectorVisualization::VectorVisualization | ( | ros::NodeHandle & | nodeHandle, |
| const std::string & | name | ||
| ) |
Constructor.
| nodeHandle | the ROS node handle. |
| name | the name of the visualization. |
Definition at line 23 of file VectorVisualization.cpp.
|
virtual |
Destructor.
Definition at line 28 of file VectorVisualization.cpp.
|
virtual |
Initialization.
Implements grid_map_visualization::VisualizationBase.
Definition at line 69 of file VectorVisualization.cpp.
|
virtual |
Read parameters from ROS.
| config | the parameters as XML. |
Reimplemented from grid_map_visualization::VisualizationBase.
Definition at line 32 of file VectorVisualization.cpp.
|
virtual |
Generates the visualization.
| map | the grid map to visualize. |
Implements grid_map_visualization::VisualizationBase.
Definition at line 80 of file VectorVisualization.cpp.
|
private |
Color of the vectors.
Definition at line 80 of file VectorVisualization.hpp.
|
private |
Width of the line markers [m].
Definition at line 77 of file VectorVisualization.hpp.
|
private |
Marker to be published.
Definition at line 65 of file VectorVisualization.hpp.
|
private |
Type that is the position of the vectors.
Definition at line 71 of file VectorVisualization.hpp.
|
private |
Scaling of the vectors.
Definition at line 74 of file VectorVisualization.hpp.
|
private |
Types that are transformed to vectors.
Definition at line 68 of file VectorVisualization.hpp.