Classes | Public Member Functions | Public Attributes | Private Attributes | List of all members
teb_local_planner::TebConfig Class Reference

Config class for the teb_local_planner and its components. More...

#include <teb_config.h>

Classes

struct  GoalTolerance
 Goal tolerance related parameters. More...
 
struct  HomotopyClasses
 
struct  Obstacles
 Obstacle related parameters. More...
 
struct  Optimization
 Optimization related parameters. More...
 
struct  Recovery
 Recovery/backup related parameters. More...
 
struct  Robot
 Robot related parameters. More...
 
struct  Trajectory
 Trajectory related parameters. More...
 

Public Member Functions

void checkDeprecated (const ros::NodeHandle &nh) const
 Check if some deprecated parameters are found and print warnings. More...
 
void checkParameters () const
 Check parameters and print warnings in case of discrepancies. More...
 
boost::mutex & configMutex ()
 Return the internal config mutex. More...
 
void loadRosParamFromNodeHandle (const ros::NodeHandle &nh)
 Load parmeters from the ros param server. More...
 
void reconfigure (TebLocalPlannerReconfigureConfig &cfg)
 Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e.g. with rosrun rqt_reconfigure rqt_reconfigure). A reconfigure server needs to be instantiated that calls this method in it's callback. In case of the plugin teb_local_planner default values are defined in PROJECT_SRC/cfg/TebLocalPlannerReconfigure.cfg. More...
 
 TebConfig ()
 Construct the TebConfig using default values. More...
 

Public Attributes

struct teb_local_planner::TebConfig::GoalTolerance goal_tolerance
 Goal tolerance related parameters. More...
 
struct teb_local_planner::TebConfig::HomotopyClasses hcp
 
std::string map_frame
 Global planning frame. More...
 
struct teb_local_planner::TebConfig::Obstacles obstacles
 Obstacle related parameters. More...
 
std::string odom_topic
 Topic name of the odometry message, provided by the robot driver or simulator. More...
 
struct teb_local_planner::TebConfig::Optimization optim
 Optimization related parameters. More...
 
struct teb_local_planner::TebConfig::Recovery recovery
 Parameters related to recovery and backup strategies. More...
 
struct teb_local_planner::TebConfig::Robot robot
 Robot related parameters. More...
 
struct teb_local_planner::TebConfig::Trajectory trajectory
 Trajectory related parameters. More...
 

Private Attributes

boost::mutex config_mutex_
 Mutex for config accesses and changes. More...
 

Detailed Description

Config class for the teb_local_planner and its components.

Definition at line 61 of file teb_config.h.

Constructor & Destructor Documentation

teb_local_planner::TebConfig::TebConfig ( )
inline

Construct the TebConfig using default values.

Warning
If the rosparam server or/and dynamic_reconfigure (rqt_reconfigure) node are used, the default variables will be overwritten:
E.g. if base_local_planner is utilized as plugin for the navigation stack, the initialize() method will register a dynamic_reconfigure server. A subset (not all but most) of the parameters are considered for dynamic modifications. All parameters considered by the dynamic_reconfigure server (and their default values) are set in PROJECT_SRC/cfg/TebLocalPlannerReconfigure.cfg.
In addition the rosparam server can be queried to get parameters e.g. defiend in a launch file. The plugin source (or a possible binary source) can call loadRosParamFromNodeHandle() to update the parameters. In summary, default parameters are loaded in the following order (the right one overrides the left ones):
TebConfig Constructor defaults << dynamic_reconfigure defaults << rosparam server defaults

Definition at line 227 of file teb_config.h.

Member Function Documentation

void teb_local_planner::TebConfig::checkDeprecated ( const ros::NodeHandle nh) const

Check if some deprecated parameters are found and print warnings.

Parameters
nhconst reference to the local ros::NodeHandle

Definition at line 331 of file teb_config.cpp.

void teb_local_planner::TebConfig::checkParameters ( ) const

Check parameters and print warnings in case of discrepancies.

Call this method whenever parameters are changed using public interfaces to inform the user about some improper uses.

Definition at line 273 of file teb_config.cpp.

boost::mutex& teb_local_planner::TebConfig::configMutex ( )
inline

Return the internal config mutex.

Definition at line 395 of file teb_config.h.

void teb_local_planner::TebConfig::loadRosParamFromNodeHandle ( const ros::NodeHandle nh)

Load parmeters from the ros param server.

Parameters
nhconst reference to the local ros::NodeHandle

Definition at line 44 of file teb_config.cpp.

void teb_local_planner::TebConfig::reconfigure ( TebLocalPlannerReconfigureConfig &  cfg)

Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e.g. with rosrun rqt_reconfigure rqt_reconfigure). A reconfigure server needs to be instantiated that calls this method in it's callback. In case of the plugin teb_local_planner default values are defined in PROJECT_SRC/cfg/TebLocalPlannerReconfigure.cfg.

Parameters
cfgConfig class autogenerated by dynamic_reconfigure according to the cfg-file mentioned above.

Definition at line 170 of file teb_config.cpp.

Member Data Documentation

boost::mutex teb_local_planner::TebConfig::config_mutex_
private

Mutex for config accesses and changes.

Definition at line 398 of file teb_config.h.

struct teb_local_planner::TebConfig::GoalTolerance teb_local_planner::TebConfig::goal_tolerance

Goal tolerance related parameters.

struct teb_local_planner::TebConfig::HomotopyClasses teb_local_planner::TebConfig::hcp
std::string teb_local_planner::TebConfig::map_frame

Global planning frame.

Definition at line 66 of file teb_config.h.

struct teb_local_planner::TebConfig::Obstacles teb_local_planner::TebConfig::obstacles

Obstacle related parameters.

std::string teb_local_planner::TebConfig::odom_topic

Topic name of the odometry message, provided by the robot driver or simulator.

Definition at line 65 of file teb_config.h.

struct teb_local_planner::TebConfig::Optimization teb_local_planner::TebConfig::optim

Optimization related parameters.

struct teb_local_planner::TebConfig::Recovery teb_local_planner::TebConfig::recovery

Parameters related to recovery and backup strategies.

struct teb_local_planner::TebConfig::Robot teb_local_planner::TebConfig::robot

Robot related parameters.

struct teb_local_planner::TebConfig::Trajectory teb_local_planner::TebConfig::trajectory

Trajectory related parameters.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 3 2020 04:03:08