Go to the documentation of this file.
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;
80 class TebVisualization
114 void publishGlobalPlan(
const std::vector<geometry_msgs::PoseStamped>& global_plan)
const;
120 void publishLocalPlan(
const std::vector<geometry_msgs::PoseStamped>& local_plan)
const;
139 void publishRobotFootprintModel(
const PoseSE2& current_pose,
const BaseRobotFootprintModel& robot_model,
const std::string& ns =
"RobotFootprintModel",
140 const std_msgs::ColorRGBA& color =
toColorMsg(0.5, 0.0, 0.8, 0.0));
142 void publishRobotFootprint(
const PoseSE2& current_pose,
const std::vector<geometry_msgs::Point>& footprint,
143 const std::string& ns,
const std_msgs::ColorRGBA &color);
153 const std::vector<geometry_msgs::Point>& footprint);
167 void publishViaPoints(
const std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >&
via_points,
const std::string& ns =
"ViaPoints")
const;
177 template <
typename GraphType>
178 void publishGraph(
const GraphType& graph,
const std::string& ns_prefix =
"Graph");
205 template <
typename B
idirIter>
206 void publishPathContainer(BidirIter first, BidirIter last,
const std::string& ns =
"PathContainer");
249 static std_msgs::ColorRGBA
toColorMsg(
double a,
double r,
double g,
double b);
265 const TebConfig*
cfg_;
271 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
void publishGraph(const GraphType &graph, const std::string &ns_prefix="Graph")
Publish a boost::adjacency_list (boost's graph datatype) via markers.
ViaPointContainer via_points
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 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.
void publishInfeasibleRobotPose(const PoseSE2 &infeasible_pose, const BaseRobotFootprintModel &robot_model, const std::vector< geometry_msgs::Point > &footprint)
Publish the robot footprint model and the actual robot footprint at an infeasible pose.
ros::Publisher feedback_pub_
Publisher for the feedback message for analysis and debug purposes.
bool printErrorWhenNotInitialized() const
Small helper function that checks if initialize() has been called and prints an error message if not.
static std_msgs::ColorRGBA toColorMsg(double a, double r, double g, double b)
Helper function to generate a color message from single values.
boost::shared_ptr< const TebVisualization > TebVisualizationConstPtr
Abbrev. for shared instances of the TebVisualization (read-only)
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)
void initialize(ros::NodeHandle &nh, const TebConfig &cfg)
Initializes the class and registers topics.
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
void publishObstacles(const ObstContainer &obstacles, double scale=0.1) const
Publish obstacle positions to the ros topic ../../teb_markers.
ros::Publisher local_plan_pub_
Publisher for the local plan.
TebVisualization()
Default constructor.
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
ros::Publisher teb_poses_pub_
Publisher for the trajectory pose sequence.
ros::Publisher global_plan_pub_
Publisher for the global plan.
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.
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 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.
void publishLocalPlanAndPoses(const TimedElasticBand &teb) const
Publish Timed_Elastic_Band related stuff (local plan, pose sequence).
void publishRobotFootprint(const PoseSE2 ¤t_pose, const std::vector< geometry_msgs::Point > &footprint, const std::string &ns, const std_msgs::ColorRGBA &color)
bool initialized_
Keeps track about the correct initialization of this class.
void publishLocalPlan(const std::vector< geometry_msgs::PoseStamped > &local_plan) const
Publish a given local plan to the ros topic ../../local_plan.
const TebConfig * cfg_
Config class that stores and manages all related parameters.
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15