39 #ifndef VISUALIZATION_H_ 40 #define VISUALIZATION_H_ 54 #include <boost/graph/adjacency_list.hpp> 55 #include <boost/graph/graph_traits.hpp> 61 #include <nav_msgs/Path.h> 62 #include <geometry_msgs/PoseStamped.h> 63 #include <geometry_msgs/PoseArray.h> 64 #include <std_msgs/ColorRGBA.h> 66 #include <nav_msgs/Odometry.h> 67 #include <nav_msgs/Path.h> 68 #include <visualization_msgs/Marker.h> 73 class TebOptimalPlanner;
114 void publishGlobalPlan(
const std::vector<geometry_msgs::PoseStamped>& global_plan)
const;
120 void publishLocalPlan(
const std::vector<geometry_msgs::PoseStamped>& local_plan)
const;
140 const std_msgs::ColorRGBA& color =
toColorMsg(0.5, 0.0, 0.8, 0.0));
161 void publishViaPoints(
const std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >&
via_points,
const std::string& ns =
"ViaPoints")
const;
171 template <
typename GraphType>
172 void publishGraph(
const GraphType& graph,
const std::string& ns_prefix =
"Graph");
199 template <
typename B
idirIter>
200 void publishPathContainer(BidirIter first, BidirIter last,
const std::string& ns =
"PathContainer");
243 static std_msgs::ColorRGBA
toColorMsg(
double a,
double r,
double g,
double b);
265 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool printErrorWhenNotInitialized() const
Small helper function that checks if initialize() has been called and prints an error message if not...
const TebConfig * cfg_
Config class that stores and manages all related parameters.
void initialize(ros::NodeHandle &nh, const TebConfig &cfg)
Initializes the class and registers topics.
ros::Publisher feedback_pub_
Publisher for the feedback message for analysis and debug purposes.
void publishPathContainer(BidirIter first, BidirIter last, const std::string &ns="PathContainer")
Publish multiple 2D paths (each path given as a point sequence) from a container class.
ros::Publisher teb_poses_pub_
Publisher for the trajectory pose sequence.
static std_msgs::ColorRGBA toColorMsg(double a, double r, double g, double b)
Helper function to generate a color message from single values.
Config class for the teb_local_planner and its components.
Class that defines a trajectory modeled as an elastic band with augmented tempoarl information...
void publishViaPoints(const std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > &via_points, const std::string &ns="ViaPoints") const
Publish via-points to the ros topic ../../teb_markers.
boost::shared_ptr< const TebVisualization > TebVisualizationConstPtr
Abbrev. for shared instances of the TebVisualization (read-only)
void publishRobotFootprintModel(const PoseSE2 ¤t_pose, const BaseRobotFootprintModel &robot_model, const std::string &ns="RobotFootprintModel", const std_msgs::ColorRGBA &color=toColorMsg(0.5, 0.0, 0.8, 0.0))
Publish the visualization of the robot model.
void publishLocalPlan(const std::vector< geometry_msgs::PoseStamped > &local_plan) const
Publish a given local plan to the ros topic ../../local_plan.
void publishTebContainer(const std::vector< boost::shared_ptr< TebOptimalPlanner > > &teb_planner, const std::string &ns="TebContainer")
Publish multiple Tebs from a container class (publish as marker message).
void publishGraph(const GraphType &graph, const std::string &ns_prefix="Graph")
Publish a boost::adjacency_list (boost's graph datatype) via markers.
void publishObstacles(const ObstContainer &obstacles) const
Publish obstacle positions to the ros topic ../../teb_markers.
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
void publishGlobalPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan) const
Publish a given global plan to the ros topic ../../global_plan.
ros::Publisher teb_marker_pub_
Publisher for visualization markers.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
TebVisualization()
Default constructor.
void publishLocalPlanAndPoses(const TimedElasticBand &teb) const
Publish Timed_Elastic_Band related stuff (local plan, pose sequence).
ros::Publisher global_plan_pub_
Publisher for the global plan.
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
void publishInfeasibleRobotPose(const PoseSE2 ¤t_pose, const BaseRobotFootprintModel &robot_model)
Publish the robot footprints related to infeasible poses.
ros::Publisher local_plan_pub_
Publisher for the local plan.
ViaPointContainer via_points
bool initialized_
Keeps track about the correct initialization of this class.
void publishFeedbackMessage(const std::vector< boost::shared_ptr< TebOptimalPlanner > > &teb_planners, unsigned int selected_trajectory_idx, const ObstContainer &obstacles)
Publish a feedback message (multiple trajectory version)