Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef VISUALIZATION_H_
00040 #define VISUALIZATION_H_
00041
00042
00043
00044
00045 #include <teb_local_planner/teb_config.h>
00046 #include <teb_local_planner/timed_elastic_band.h>
00047 #include <teb_local_planner/robot_footprint_model.h>
00048
00049
00050 #include <ros/publisher.h>
00051 #include <base_local_planner/goal_functions.h>
00052
00053
00054 #include <boost/graph/adjacency_list.hpp>
00055 #include <boost/graph/graph_traits.hpp>
00056
00057
00058 #include <iterator>
00059
00060
00061 #include <nav_msgs/Path.h>
00062 #include <geometry_msgs/PoseStamped.h>
00063 #include <geometry_msgs/PoseArray.h>
00064 #include <tf/transform_datatypes.h>
00065 #include <nav_msgs/Odometry.h>
00066 #include <nav_msgs/Path.h>
00067 #include <visualization_msgs/Marker.h>
00068
00069 namespace teb_local_planner
00070 {
00071
00072 class TebOptimalPlanner;
00073
00074
00079 class TebVisualization
00080 {
00081 public:
00082
00087 TebVisualization();
00088
00094 TebVisualization(ros::NodeHandle& nh, const std::string& visualization_frame);
00095
00103 void initialize(ros::NodeHandle& nh, const std::string& visualization_frame);
00104
00105
00108
00113 void publishGlobalPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan) const;
00114
00119 void publishLocalPlan(const std::vector<geometry_msgs::PoseStamped>& local_plan) const;
00120
00128 void publishLocalPlanAndPoses(const TimedElasticBand& teb) const;
00129
00137 void publishRobotFootprintModel(const PoseSE2& current_pose, const BaseRobotFootprintModel& robot_model, const std::string& ns = "RobotFootprintModel");
00138
00144 void publishObstacles(const ObstContainer& obstacles) const;
00145
00150 void publishViaPoints(const std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >& via_points, const std::string& ns = "ViaPoints") const;
00151
00160 template <typename GraphType>
00161 void publishGraph(const GraphType& graph, const std::string& ns_prefix = "Graph");
00162
00188 template <typename BidirIter>
00189 void publishPathContainer(BidirIter first, BidirIter last, const std::string& ns = "PathContainer");
00190
00197 void publishTebContainer(const std::vector< boost::shared_ptr<TebOptimalPlanner> >& teb_planner, const std::string& ns = "TebContainer");
00198
00209 void publishFeedbackMessage(const std::vector< boost::shared_ptr<TebOptimalPlanner> >& teb_planners, unsigned int selected_trajectory_idx, const ObstContainer& obstacles);
00210
00220 void publishFeedbackMessage(const TebOptimalPlanner& teb_planner, const ObstContainer& obstacles);
00221
00223
00224 protected:
00225
00230 bool printErrorWhenNotInitialized() const;
00231
00232 ros::Publisher global_plan_pub_;
00233 ros::Publisher local_plan_pub_;
00234 ros::Publisher teb_poses_pub_;
00235 ros::Publisher teb_marker_pub_;
00236 ros::Publisher feedback_pub_;
00237
00238 std::string visualization_frame_ = "map";
00239
00240 bool initialized_;
00241
00242
00243 public:
00244 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00245 };
00246
00248 typedef boost::shared_ptr<TebVisualization> TebVisualizationPtr;
00249
00251 typedef boost::shared_ptr<const TebVisualization> TebVisualizationConstPtr;
00252
00253
00254 }
00255
00256
00257
00258 #include <teb_local_planner/visualization.hpp>
00259
00260 #endif