38 #ifndef EBAND_VISUALIZATION_H_ 39 #define EBAND_VISUALIZATION_H_ 46 #include <eband_local_planner/EBandPlannerConfig.h> 49 #include <geometry_msgs/Pose2D.h> 50 #include <geometry_msgs/Pose.h> 51 #include <geometry_msgs/PoseStamped.h> 52 #include <geometry_msgs/Wrench.h> 53 #include <geometry_msgs/WrenchStamped.h> 55 #include <visualization_msgs/Marker.h> 56 #include <visualization_msgs/MarkerArray.h> 68 #include <Eigen/Geometry> 120 void publishBand(std::string marker_name_space, std::vector<Bubble> band);
146 void publishForceList(std::string marker_name_space, std::vector<geometry_msgs::WrenchStamped> forces, std::vector<Bubble> band);
154 void publishForce(std::string marker_name_space,
int id,
Color marker_color, geometry_msgs::WrenchStamped force,
Bubble bubble);
181 void bubbleToMarker(
Bubble bubble, visualization_msgs::Marker& marker, std::string marker_name_space,
int marker_id,
Color marker_color);
201 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);
void reconfigure(EBandPlannerConfig &config)
Reconfigures the parameters of the planner.
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 publishBubble(std::string marker_name_space, int marker_id, Bubble bubble)
publishes a single bubble as a Marker
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 publishBand(std::string marker_name_space, std::vector< Bubble > band)
publishes the bubbles (Position and Expansion) in a band as Marker-Array
ros::Publisher one_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
~EBandVisualization()
Default destructor.
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
void initialize(ros::NodeHandle &pn, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the visualization class.
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
ros::Publisher bubble_pub_
publishes markers to visualize bubbles of elastic band ("modified global plan")
EBandVisualization()
Default constructor.
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