Public Member Functions | Static Public Member Functions | Private Types | Private Attributes | List of all members
mpc_local_planner::Publisher Class Reference

This class provides publishing methods for common messages. More...

#include <publisher.h>

Public Member Functions

void initialize (ros::NodeHandle &nh, RobotDynamicsInterface::Ptr system, const std::string &map_frame)
 Initializes the class and registers topics. More...
 
 Publisher ()=default
 Default constructor. More...
 
 Publisher (ros::NodeHandle &nh, RobotDynamicsInterface::Ptr system, const std::string &map_frame)
 Constructor that initializes the class and registers topics. More...
 
void publishGlobalPlan (const std::vector< geometry_msgs::PoseStamped > &global_plan) const
 Publish a given global plan to the ros topic ../../global_plan. More...
 
void publishLocalPlan (const corbo::TimeSeries &ts) const
 Publish a given local plan to the ros topic ../../local_plan. More...
 
void publishLocalPlan (const std::vector< geometry_msgs::PoseStamped > &local_plan) const
 Publish a given local plan to the ros topic ../../local_plan. More...
 
void publishObstacles (const teb_local_planner::ObstContainer &obstacles) const
 Publish obstacle positions to the ros topic ../../mpc_markers. More...
 
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. More...
 
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. More...
 

Static Public Member Functions

static std_msgs::ColorRGBA toColorMsg (float a, float r, float g, float b)
 Helper function to generate a color message from single values. More...
 

Private Types

using CircularObstacle = teb_local_planner::CircularObstacle
 
using LineObstacle = teb_local_planner::LineObstacle
 
using ObstaclePtr = teb_local_planner::ObstaclePtr
 
using ObstContainer = teb_local_planner::ObstContainer
 
using Point2dContainer = teb_local_planner::Point2dContainer
 
using PointObstacle = teb_local_planner::PointObstacle
 
using PolygonObstacle = teb_local_planner::PolygonObstacle
 

Private Attributes

ros::Publisher _global_plan_pub
 
bool _initialized = false
 
ros::Publisher _local_plan_pub
 
std::string _map_frame = "map"
 
ros::Publisher _mpc_marker_pub
 
RobotDynamicsInterface::Ptr _system
 

Detailed Description

This class provides publishing methods for common messages.

Author
Christoph Rösmann (chris.nosp@m.toph.nosp@m..roes.nosp@m.mann.nosp@m.@tu-d.nosp@m.ortm.nosp@m.und.d.nosp@m.e)

Definition at line 66 of file publisher.h.

Member Typedef Documentation

◆ CircularObstacle

Definition at line 91 of file publisher.h.

◆ LineObstacle

Definition at line 92 of file publisher.h.

◆ ObstaclePtr

Definition at line 88 of file publisher.h.

◆ ObstContainer

Definition at line 89 of file publisher.h.

◆ Point2dContainer

Definition at line 94 of file publisher.h.

◆ PointObstacle

Definition at line 90 of file publisher.h.

◆ PolygonObstacle

Definition at line 93 of file publisher.h.

Constructor & Destructor Documentation

◆ Publisher() [1/2]

mpc_local_planner::Publisher::Publisher ( )
default

Default constructor.

Remarks
do not forget to call initialize()

◆ Publisher() [2/2]

mpc_local_planner::Publisher::Publisher ( ros::NodeHandle nh,
RobotDynamicsInterface::Ptr  system,
const std::string &  map_frame 
)

Constructor that initializes the class and registers topics.

Parameters
[in]nhlocal ros::NodeHandle
[in]map_framethe planning frame name

Definition at line 61 of file publisher.cpp.

Member Function Documentation

◆ initialize()

void mpc_local_planner::Publisher::initialize ( ros::NodeHandle nh,
RobotDynamicsInterface::Ptr  system,
const std::string &  map_frame 
)

Initializes the class and registers topics.

Call this function if only the default constructor has been called before.

Parameters
[in]nhlocal ros::NodeHandle
[in]map_framethe planning frame name

Definition at line 63 of file publisher.cpp.

◆ publishGlobalPlan()

void mpc_local_planner::Publisher::publishGlobalPlan ( const std::vector< geometry_msgs::PoseStamped > &  global_plan) const

Publish a given global plan to the ros topic ../../global_plan.

Parameters
[in]global_planPose array describing the global plan

Definition at line 98 of file publisher.cpp.

◆ publishLocalPlan() [1/2]

void mpc_local_planner::Publisher::publishLocalPlan ( const corbo::TimeSeries ts) const

Publish a given local plan to the ros topic ../../local_plan.

Parameters
[in]local_planPose array describing the local plan

Definition at line 84 of file publisher.cpp.

◆ publishLocalPlan() [2/2]

void mpc_local_planner::Publisher::publishLocalPlan ( const std::vector< geometry_msgs::PoseStamped > &  local_plan) const

Publish a given local plan to the ros topic ../../local_plan.

Parameters
[in]local_planPose array describing the local plan

Definition at line 78 of file publisher.cpp.

◆ publishObstacles()

void mpc_local_planner::Publisher::publishObstacles ( const teb_local_planner::ObstContainer obstacles) const

Publish obstacle positions to the ros topic ../../mpc_markers.

Todo:
Move filling of the marker message to polygon class in order to avoid checking types.
Parameters
[in]obstaclesObstacle container

Definition at line 127 of file publisher.cpp.

◆ publishRobotFootprintModel()

void mpc_local_planner::Publisher::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.

Parameters
[in]current_poseCurrent pose of the robot
[in]robot_modelSubclass of BaseRobotFootprintModel
[in]map_frameframe name for the msg header
[in]nsNamespace for the marker objects
[in]colorColor of the footprint

Definition at line 104 of file publisher.cpp.

◆ publishViaPoints()

void mpc_local_planner::Publisher::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.

Todo:
add option to switch between points and poses (including orientation) to be published
Parameters
[in]via_pointsvia-point container
[in]nsmarker namespace

Definition at line 254 of file publisher.cpp.

◆ toColorMsg()

std_msgs::ColorRGBA mpc_local_planner::Publisher::toColorMsg ( float  a,
float  r,
float  g,
float  b 
)
static

Helper function to generate a color message from single values.

Parameters
[in]aAlpha value
[in]rRed value
[in]gGreen value
[in]bBlue value
Returns
Color message

Definition at line 286 of file publisher.cpp.

Member Data Documentation

◆ _global_plan_pub

ros::Publisher mpc_local_planner::Publisher::_global_plan_pub
private

Definition at line 184 of file publisher.h.

◆ _initialized

bool mpc_local_planner::Publisher::_initialized = false
private

Definition at line 177 of file publisher.h.

◆ _local_plan_pub

ros::Publisher mpc_local_planner::Publisher::_local_plan_pub
private

Definition at line 183 of file publisher.h.

◆ _map_frame

std::string mpc_local_planner::Publisher::_map_frame = "map"
private

Definition at line 179 of file publisher.h.

◆ _mpc_marker_pub

ros::Publisher mpc_local_planner::Publisher::_mpc_marker_pub
private

Definition at line 185 of file publisher.h.

◆ _system

RobotDynamicsInterface::Ptr mpc_local_planner::Publisher::_system
private

Definition at line 181 of file publisher.h.


The documentation for this class was generated from the following files:


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