#include <eband_visualization.h>
Public Types | |
enum | Color { blue, red, green } |
Public Member Functions | |
EBandVisualization () | |
Default constructor. | |
EBandVisualization (ros::NodeHandle &pn, costmap_2d::Costmap2DROS *costmap_ros) | |
Construct and initializes eband visualization. | |
void | initialize (ros::NodeHandle &pn, costmap_2d::Costmap2DROS *costmap_ros) |
Initializes the visualization class. | |
void | publishBand (std::string marker_name_space, std::vector< Bubble > band) |
publishes the bubbles (Position and Expansion) in a band as Marker-Array | |
void | publishBubble (std::string marker_name_space, int marker_id, Bubble bubble) |
publishes a single bubble as a Marker | |
void | publishBubble (std::string marker_name_space, int marker_id, Color marker_color, Bubble bubble) |
publishes a single bubble as a Marker | |
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 | |
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 | |
~EBandVisualization () | |
Default destructor. | |
Private Member Functions | |
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 | |
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 | |
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 | |
Private Attributes | |
ros::Publisher | bubble_pub_ |
publishes markers to visualize bubbles of elastic band ("modified global plan") | |
costmap_2d::Costmap2DROS * | costmap_ros_ |
pointer to costmap - needed to retrieve information about robot geometry | |
bool | initialized_ |
double | marker_lifetime_ |
ros::Publisher | one_bubble_pub_ |
publishes markers to visualize bubbles of elastic band ("modified global plan") |
Definition at line 76 of file eband_visualization.h.
Definition at line 81 of file eband_visualization.h.
Default constructor.
Definition at line 45 of file eband_visualization.cpp.
eband_local_planner::EBandVisualization::EBandVisualization | ( | ros::NodeHandle & | pn, |
costmap_2d::Costmap2DROS * | costmap_ros | ||
) |
Construct and initializes eband visualization.
Definition at line 48 of file eband_visualization.cpp.
Default destructor.
Definition at line 54 of file eband_visualization.cpp.
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
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 247 of file eband_visualization.cpp.
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
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 205 of file eband_visualization.cpp.
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
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 289 of file eband_visualization.cpp.
void eband_local_planner::EBandVisualization::initialize | ( | ros::NodeHandle & | pn, |
costmap_2d::Costmap2DROS * | costmap_ros | ||
) |
Initializes the visualization class.
name | The name to give this instance (important for publishing) |
Definition at line 57 of file eband_visualization.cpp.
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
the | name space under which the markers shall be bublished |
the | shape of the markers |
the | band which shall be published |
Definition at line 82 of file eband_visualization.cpp.
void eband_local_planner::EBandVisualization::publishBubble | ( | std::string | marker_name_space, |
int | marker_id, | ||
Bubble | bubble | ||
) |
publishes a single bubble as a Marker
the | name space under which the markers shall be bublished |
the | shape of the markers |
the | bubble which shall be published |
Definition at line 115 of file eband_visualization.cpp.
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
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 134 of file eband_visualization.cpp.
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
the | name space under which the markers shall be bublished |
the | shape of the markers |
the | force which shall be published |
Definition at line 186 of file eband_visualization.cpp.
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
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 153 of file eband_visualization.cpp.
publishes markers to visualize bubbles of elastic band ("modified global plan")
Definition at line 155 of file eband_visualization.h.
pointer to costmap - needed to retrieve information about robot geometry
Definition at line 152 of file eband_visualization.h.
bool eband_local_planner::EBandVisualization::initialized_ [private] |
Definition at line 159 of file eband_visualization.h.
double eband_local_planner::EBandVisualization::marker_lifetime_ [private] |
Definition at line 162 of file eband_visualization.h.
publishes markers to visualize bubbles of elastic band ("modified global plan")
Definition at line 156 of file eband_visualization.h.