#include <eband_visualization.h>
|
| | EBandVisualization () |
| | Default constructor. More...
|
| |
| | EBandVisualization (ros::NodeHandle &pn, costmap_2d::Costmap2DROS *costmap_ros) |
| | Construct and initializes eband visualization. More...
|
| |
| void | initialize (ros::NodeHandle &pn, costmap_2d::Costmap2DROS *costmap_ros) |
| | Initializes the visualization class. More...
|
| |
| void | publishBand (std::string marker_name_space, std::vector< Bubble > band) |
| | publishes the bubbles (Position and Expansion) in a band as Marker-Array More...
|
| |
| void | publishBubble (std::string marker_name_space, int marker_id, Bubble bubble) |
| | publishes a single bubble as a Marker More...
|
| |
| void | publishBubble (std::string marker_name_space, int marker_id, Color marker_color, Bubble bubble) |
| | publishes a single bubble as a Marker More...
|
| |
| void | publishForce (std::string marker_name_space, int id, Color marker_color, geometry_msgs::WrenchStamped force, Bubble bubble) |
| | publishes a single force as a Marker More...
|
| |
| void | publishForceList (std::string marker_name_space, std::vector< geometry_msgs::WrenchStamped > forces, std::vector< Bubble > band) |
| | publishes the list of forces along the band as Marker-Array More...
|
| |
| void | reconfigure (EBandPlannerConfig &config) |
| | Reconfigures the parameters of the planner. More...
|
| |
| | ~EBandVisualization () |
| | Default destructor. More...
|
| |
|
| void | bubbleHeadingToMarker (Bubble bubble, visualization_msgs::Marker &marker, std::string marker_name_space, int marker_id, Color marker_color) |
| | converts the haeding of a bubble into a Arrow-Marker msg - this is visualization-specific More...
|
| |
| void | bubbleToMarker (Bubble bubble, visualization_msgs::Marker &marker, std::string marker_name_space, int marker_id, Color marker_color) |
| | converts a bubble into a Marker msg - this is visualization-specific More...
|
| |
| void | forceToMarker (geometry_msgs::WrenchStamped wrench, geometry_msgs::Pose wrench_origin, visualization_msgs::Marker &marker, std::string marker_name_space, int marker_id, Color marker_color) |
| | converts a wrench into a Marker msg - this is visualization-specific More...
|
| |
Definition at line 79 of file eband_visualization.h.
◆ Color
◆ EBandVisualization() [1/2]
| eband_local_planner::EBandVisualization::EBandVisualization |
( |
| ) |
|
◆ EBandVisualization() [2/2]
◆ ~EBandVisualization()
| eband_local_planner::EBandVisualization::~EBandVisualization |
( |
| ) |
|
◆ bubbleHeadingToMarker()
| void eband_local_planner::EBandVisualization::bubbleHeadingToMarker |
( |
Bubble |
bubble, |
|
|
visualization_msgs::Marker & |
marker, |
|
|
std::string |
marker_name_space, |
|
|
int |
marker_id, |
|
|
Color |
marker_color |
|
) |
| |
|
private |
converts the haeding of a bubble into a Arrow-Marker msg - this is visualization-specific
- Parameters
-
| the | bubble to convert |
| reference | to hand back the marker |
| name | space under which the marker shall be published |
| object | id of the marker in its name space |
Definition at line 254 of file eband_visualization.cpp.
◆ bubbleToMarker()
| void eband_local_planner::EBandVisualization::bubbleToMarker |
( |
Bubble |
bubble, |
|
|
visualization_msgs::Marker & |
marker, |
|
|
std::string |
marker_name_space, |
|
|
int |
marker_id, |
|
|
Color |
marker_color |
|
) |
| |
|
private |
converts a bubble into a Marker msg - this is visualization-specific
- Parameters
-
| the | bubble to convert |
| reference | to hand back the marker |
| name | space under which the marker shall be published |
| object | id of the marker in its name space |
Definition at line 212 of file eband_visualization.cpp.
◆ forceToMarker()
| void eband_local_planner::EBandVisualization::forceToMarker |
( |
geometry_msgs::WrenchStamped |
wrench, |
|
|
geometry_msgs::Pose |
wrench_origin, |
|
|
visualization_msgs::Marker & |
marker, |
|
|
std::string |
marker_name_space, |
|
|
int |
marker_id, |
|
|
Color |
marker_color |
|
) |
| |
|
private |
converts a wrench into a Marker msg - this is visualization-specific
- Parameters
-
| the | wrench to convert |
| origin | of force or wrench |
| reference | to hand back the marker |
| name | space under which the marker shall be published |
| object | id of the marker in its name space |
| color | in which the marker shall be displayed |
Definition at line 296 of file eband_visualization.cpp.
◆ initialize()
Initializes the visualization class.
- Parameters
-
| name | The name to give this instance (important for publishing) |
Definition at line 57 of file eband_visualization.cpp.
◆ publishBand()
| void eband_local_planner::EBandVisualization::publishBand |
( |
std::string |
marker_name_space, |
|
|
std::vector< Bubble > |
band |
|
) |
| |
publishes the bubbles (Position and Expansion) in a band as Marker-Array
- Parameters
-
| the | name space under which the markers shall be bublished |
| the | shape of the markers |
| the | band which shall be published |
Definition at line 89 of file eband_visualization.cpp.
◆ publishBubble() [1/2]
| void eband_local_planner::EBandVisualization::publishBubble |
( |
std::string |
marker_name_space, |
|
|
int |
marker_id, |
|
|
Bubble |
bubble |
|
) |
| |
publishes a single bubble as a Marker
- Parameters
-
| the | name space under which the markers shall be bublished |
| the | shape of the markers |
| the | bubble which shall be published |
Definition at line 122 of file eband_visualization.cpp.
◆ publishBubble() [2/2]
| void eband_local_planner::EBandVisualization::publishBubble |
( |
std::string |
marker_name_space, |
|
|
int |
marker_id, |
|
|
Color |
marker_color, |
|
|
Bubble |
bubble |
|
) |
| |
publishes a single bubble as a Marker
- Parameters
-
| the | name space under which the markers shall be bublished |
| the | shape of the markers |
| the | bubble which shall be published |
| color | in which the bubble shall be displayed |
Definition at line 141 of file eband_visualization.cpp.
◆ publishForce()
| void eband_local_planner::EBandVisualization::publishForce |
( |
std::string |
marker_name_space, |
|
|
int |
id, |
|
|
Color |
marker_color, |
|
|
geometry_msgs::WrenchStamped |
force, |
|
|
Bubble |
bubble |
|
) |
| |
publishes a single force as a Marker
- Parameters
-
| the | name space under which the markers shall be bublished |
| the | shape of the markers |
| the | force which shall be published |
Definition at line 193 of file eband_visualization.cpp.
◆ publishForceList()
| void eband_local_planner::EBandVisualization::publishForceList |
( |
std::string |
marker_name_space, |
|
|
std::vector< geometry_msgs::WrenchStamped > |
forces, |
|
|
std::vector< Bubble > |
band |
|
) |
| |
publishes the list of forces along the band as Marker-Array
- Parameters
-
| the | name space under which the markers shall be bublished |
| the | shape of the markers |
| the | list of forces which shall be published |
| the | list of bubbles on which the forces act (needed to get origin of force-vector) |
Definition at line 160 of file eband_visualization.cpp.
◆ reconfigure()
| void eband_local_planner::EBandVisualization::reconfigure |
( |
EBandPlannerConfig & |
config | ) |
|
Reconfigures the parameters of the planner.
- Parameters
-
| config | The dynamic reconfigure configuration |
Definition at line 82 of file eband_visualization.cpp.
◆ bubble_pub_
publishes markers to visualize bubbles of elastic band ("modified global plan")
Definition at line 164 of file eband_visualization.h.
◆ costmap_ros_
pointer to costmap - needed to retrieve information about robot geometry
Definition at line 161 of file eband_visualization.h.
◆ initialized_
| bool eband_local_planner::EBandVisualization::initialized_ |
|
private |
◆ marker_lifetime_
| double eband_local_planner::EBandVisualization::marker_lifetime_ |
|
private |
◆ one_bubble_pub_
| ros::Publisher eband_local_planner::EBandVisualization::one_bubble_pub_ |
|
private |
publishes markers to visualize bubbles of elastic band ("modified global plan")
Definition at line 165 of file eband_visualization.h.
The documentation for this class was generated from the following files: