publisher.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020, Christoph Rösmann, All rights reserved.
6  *
7  * This program is free software: you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation, either version 3 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <https://www.gnu.org/licenses/>.
19  *
20  * Authors: Christoph Rösmann
21  *********************************************************************/
22 
23 #ifndef UTILS_PUBLISHER_H_
24 #define UTILS_PUBLISHER_H_
25 
26 #include <corbo-core/time_series.h>
27 #include <corbo-core/types.h>
31 
32 #include <geometry_msgs/PoseStamped.h>
33 #include <ros/publisher.h>
34 #include <ros/ros.h>
35 #include <std_msgs/ColorRGBA.h>
36 
37 #include <memory>
38 
39 namespace mpc_local_planner {
40 
46 class Publisher
47 {
55 
56  public:
61  Publisher() = default;
62 
68  Publisher(ros::NodeHandle& nh, RobotDynamicsInterface::Ptr system, const std::string& map_frame);
69 
77  void initialize(ros::NodeHandle& nh, RobotDynamicsInterface::Ptr system, const std::string& map_frame);
78 
83  void publishLocalPlan(const std::vector<geometry_msgs::PoseStamped>& local_plan) const;
84 
89  void publishLocalPlan(const corbo::TimeSeries& ts) const;
90 
95  void publishGlobalPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan) const;
96 
107  const std::string& ns = "RobotFootprintModel", const std_msgs::ColorRGBA& color = toColorMsg(0.5, 0.0, 0.8, 0.0));
108 
114  void publishObstacles(const teb_local_planner::ObstContainer& obstacles) const;
115 
124  void publishViaPoints(const std::vector<teb_local_planner::PoseSE2>& via_points, const std::string& ns = "ViaPoints") const;
125 
134  static std_msgs::ColorRGBA toColorMsg(float a, float r, float g, float b);
135 
136  private:
137  bool _initialized = false;
138 
139  std::string _map_frame = "map";
140 
142 
146 };
147 
148 } // namespace mpc_local_planner
149 
150 #endif // UTILS_PUBLISHER_H_
mpc_local_planner::Publisher::Publisher
Publisher()=default
Default constructor.
ros::Publisher
boost::shared_ptr
mpc_local_planner::Publisher::publishRobotFootprintModel
void publishRobotFootprintModel(const teb_local_planner::PoseSE2 &current_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.
Definition: publisher.cpp:104
mpc_local_planner::Publisher::PointObstacle
teb_local_planner::PointObstacle PointObstacle
Definition: publisher.h:90
mpc_local_planner::Publisher::publishViaPoints
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.
Definition: publisher.cpp:254
mpc_local_planner::Publisher::_map_frame
std::string _map_frame
Definition: publisher.h:179
ros.h
mpc_local_planner::Publisher::_local_plan_pub
ros::Publisher _local_plan_pub
Definition: publisher.h:183
Point2dContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
robot_dynamics_interface.h
teb_local_planner::BaseRobotFootprintModel
mpc_local_planner::Publisher::_initialized
bool _initialized
Definition: publisher.h:177
publisher.h
mpc_local_planner
Definition: controller.h:44
mpc_local_planner::Publisher::initialize
void initialize(ros::NodeHandle &nh, RobotDynamicsInterface::Ptr system, const std::string &map_frame)
Initializes the class and registers topics.
Definition: publisher.cpp:63
teb_local_planner::ObstaclePtr
boost::shared_ptr< Obstacle > ObstaclePtr
teb_local_planner::CircularObstacle
mpc_local_planner::Publisher::_global_plan_pub
ros::Publisher _global_plan_pub
Definition: publisher.h:184
mpc_local_planner::Publisher::PolygonObstacle
teb_local_planner::PolygonObstacle PolygonObstacle
Definition: publisher.h:93
ObstContainer
std::vector< ObstaclePtr > ObstContainer
robot_footprint_model.h
mpc_local_planner::Publisher::_system
RobotDynamicsInterface::Ptr _system
Definition: publisher.h:181
time_series.h
teb_local_planner::PointObstacle
corbo::TimeSeries
mpc_local_planner::Publisher::CircularObstacle
teb_local_planner::CircularObstacle CircularObstacle
Definition: publisher.h:91
teb_local_planner::PoseSE2
teb_local_planner::LineObstacle
mpc_local_planner::Publisher::toColorMsg
static std_msgs::ColorRGBA toColorMsg(float a, float r, float g, float b)
Helper function to generate a color message from single values.
Definition: publisher.cpp:286
mpc_local_planner::Publisher::publishGlobalPlan
void publishGlobalPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan) const
Publish a given global plan to the ros topic ../../global_plan.
Definition: publisher.cpp:98
mpc_local_planner::Publisher::_mpc_marker_pub
ros::Publisher _mpc_marker_pub
Definition: publisher.h:185
teb_local_planner::PolygonObstacle
obstacles.h
mpc_local_planner::Publisher::LineObstacle
teb_local_planner::LineObstacle LineObstacle
Definition: publisher.h:92
mpc_local_planner::Publisher::publishLocalPlan
void publishLocalPlan(const std::vector< geometry_msgs::PoseStamped > &local_plan) const
Publish a given local plan to the ros topic ../../local_plan.
Definition: publisher.cpp:78
mpc_local_planner::Publisher::publishObstacles
void publishObstacles(const teb_local_planner::ObstContainer &obstacles) const
Publish obstacle positions to the ros topic ../../mpc_markers.
Definition: publisher.cpp:127
ros::NodeHandle
mpc_local_planner::RobotDynamicsInterface::Ptr
std::shared_ptr< RobotDynamicsInterface > Ptr
Definition: robot_dynamics_interface.h:89


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06