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 | 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. |
Config class for the teb_local_planner and its components.
Definition at line 61 of file teb_config.h.
teb_local_planner::TebConfig::TebConfig | ( | ) | [inline] |
Construct the TebConfig using default values.
Definition at line 199 of file teb_config.h.
void teb_local_planner::TebConfig::checkDeprecated | ( | const ros::NodeHandle & | nh | ) | const |
Check if some deprecated parameters are found and print warnings.
nh | const reference to the local ros::NodeHandle |
Definition at line 287 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 236 of file teb_config.cpp.
boost::mutex& teb_local_planner::TebConfig::configMutex | ( | ) | [inline] |
Return the internal config mutex.
Definition at line 341 of file teb_config.h.
void teb_local_planner::TebConfig::loadRosParamFromNodeHandle | ( | const ros::NodeHandle & | nh | ) |
Load parmeters from the ros param server.
nh | const 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.
cfg | Config class autogenerated by dynamic_reconfigure according to the cfg-file mentioned above. |
Definition at line 143 of file teb_config.cpp.
boost::mutex teb_local_planner::TebConfig::config_mutex_ [private] |
Mutex for config accesses and changes.
Definition at line 344 of file teb_config.h.
Goal tolerance related parameters.
std::string teb_local_planner::TebConfig::map_frame |
Global planning frame.
Definition at line 66 of file teb_config.h.
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.
Optimization related parameters.
Robot related parameters.
Trajectory related parameters.