Go to the documentation of this file.
23 #ifndef UTILS_PUBLISHER_H_
24 #define UTILS_PUBLISHER_H_
27 #include <corbo-core/types.h>
32 #include <geometry_msgs/PoseStamped.h>
35 #include <std_msgs/ColorRGBA.h>
83 void publishLocalPlan(
const std::vector<geometry_msgs::PoseStamped>& local_plan)
const;
95 void publishGlobalPlan(
const std::vector<geometry_msgs::PoseStamped>& global_plan)
const;
107 const std::string& ns =
"RobotFootprintModel",
const std_msgs::ColorRGBA& color =
toColorMsg(0.5, 0.0, 0.8, 0.0));
124 void publishViaPoints(
const std::vector<teb_local_planner::PoseSE2>& via_points,
const std::string& ns =
"ViaPoints")
const;
134 static std_msgs::ColorRGBA
toColorMsg(
float a,
float r,
float g,
float b);
150 #endif // UTILS_PUBLISHER_H_
Publisher()=default
Default constructor.
void publishRobotFootprintModel(const teb_local_planner::PoseSE2 ¤t_pose, const teb_local_planner::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.
teb_local_planner::PointObstacle PointObstacle
void publishViaPoints(const std::vector< teb_local_planner::PoseSE2 > &via_points, const std::string &ns="ViaPoints") const
Publish via-points to the ros topic ../../teb_markers.
ros::Publisher _local_plan_pub
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
void initialize(ros::NodeHandle &nh, RobotDynamicsInterface::Ptr system, const std::string &map_frame)
Initializes the class and registers topics.
boost::shared_ptr< Obstacle > ObstaclePtr
ros::Publisher _global_plan_pub
teb_local_planner::PolygonObstacle PolygonObstacle
std::vector< ObstaclePtr > ObstContainer
RobotDynamicsInterface::Ptr _system
teb_local_planner::CircularObstacle CircularObstacle
static std_msgs::ColorRGBA toColorMsg(float a, float r, float g, float b)
Helper function to generate a color message from single values.
void publishGlobalPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan) const
Publish a given global plan to the ros topic ../../global_plan.
ros::Publisher _mpc_marker_pub
teb_local_planner::LineObstacle LineObstacle
void publishLocalPlan(const std::vector< geometry_msgs::PoseStamped > &local_plan) const
Publish a given local plan to the ros topic ../../local_plan.
void publishObstacles(const teb_local_planner::ObstContainer &obstacles) const
Publish obstacle positions to the ros topic ../../mpc_markers.
std::shared_ptr< RobotDynamicsInterface > Ptr
mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06