Classes | Public Member Functions | Public Attributes | Private Attributes
teb_local_planner::TebConfig Class Reference

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

#include <teb_config.h>

List of all members.

Classes

struct  GoalTolerance
 Goal tolerance related parameters. More...
struct  HomotopyClasses
struct  Obstacles
 Obstacle related parameters. More...
struct  Optimization
 Optimization 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.
void checkParameters () const
 Check parameters and print warnings in case of discrepancies.
boost::mutex & configMutex ()
 Return the internal config mutex.
void loadRosParamFromNodeHandle (const ros::NodeHandle &nh)
 Load parmeters from the ros param server.
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.
 TebConfig ()
 Construct the TebConfig using default values.

Public Attributes

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

Private Attributes

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

Detailed Description

Config class for the teb_local_planner and its components.

Definition at line 61 of file teb_config.h.


Constructor & Destructor Documentation

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 184 of file teb_config.h.


Member Function Documentation

Check if some deprecated parameters are found and print warnings.

Parameters:
nhconst reference to the local ros::NodeHandle

Definition at line 257 of file teb_config.cpp.

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 210 of file teb_config.cpp.

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

Return the internal config mutex.

Definition at line 311 of file teb_config.h.

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 129 of file teb_config.cpp.


Member Data Documentation

Mutex for config accesses and changes.

Definition at line 314 of file teb_config.h.

Goal tolerance related parameters.

Global planning frame.

Definition at line 66 of file teb_config.h.

Obstacle related parameters.

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

Definition at line 65 of file teb_config.h.

Optimization related parameters.

Robot related parameters.

Trajectory related parameters.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:16