A class to define a planner configuration. More...
#include <ompl_ros_planner_config.h>
Public Member Functions | |
const std::string & | getName (void) |
Return the name of the planner configuration parameter. | |
double | getParamDouble (const std::string ¶m, double def) |
Get a double parameter. | |
int | getParamInt (const std::string ¶m, int def) |
Get a integer parameter. | |
std::string | getParamString (const std::string ¶m, const std::string &def="") |
Get a string parameter. | |
bool | hasParam (const std::string ¶m) |
Check whether the particular parameter exists on the parameter server within the namespace defined by the planner configuration. | |
PlannerConfig (const std::string &description, const std::string &config) | |
Default constructor. | |
~PlannerConfig (void) | |
Private Attributes | |
std::string | config_ |
std::string | description_ |
ros::NodeHandle | nh_ |
A class to define a planner configuration.
Definition at line 53 of file ompl_ros_planner_config.h.
ompl_ros_interface::PlannerConfig::PlannerConfig | ( | const std::string & | description, |
const std::string & | config | ||
) | [inline] |
Default constructor.
description | - the namespace containing the parameters corresponding to the planner |
config | - the actual name of the configuration space for this planner, the parameters will be read from the ROS parameter server at "description/config". |
Definition at line 62 of file ompl_ros_planner_config.h.
ompl_ros_interface::PlannerConfig::~PlannerConfig | ( | void | ) | [inline] |
Definition at line 66 of file ompl_ros_planner_config.h.
const std::string & ompl_ros_interface::PlannerConfig::getName | ( | void | ) |
Return the name of the planner configuration parameter.
Definition at line 41 of file ompl_ros_planner_config.cpp.
double ompl_ros_interface::PlannerConfig::getParamDouble | ( | const std::string & | param, |
double | def | ||
) |
Get a double parameter.
param | - the name of the parameter to get |
def | (optional) - the return value if the parameter does not exist |
Definition at line 59 of file ompl_ros_planner_config.cpp.
int ompl_ros_interface::PlannerConfig::getParamInt | ( | const std::string & | param, |
int | def | ||
) |
Get a integer parameter.
param | - the name of the parameter to get |
def | (optional) - the return value if the parameter does not exist |
Definition at line 66 of file ompl_ros_planner_config.cpp.
std::string ompl_ros_interface::PlannerConfig::getParamString | ( | const std::string & | param, |
const std::string & | def = "" |
||
) |
Get a string parameter.
param | - the string parameter to get |
def | (optional) - the return value if the parameter does not exist |
Definition at line 51 of file ompl_ros_planner_config.cpp.
bool ompl_ros_interface::PlannerConfig::hasParam | ( | const std::string & | param | ) |
Check whether the particular parameter exists on the parameter server within the namespace defined by the planner configuration.
param | - the string name of the parameter to look for |
Definition at line 46 of file ompl_ros_planner_config.cpp.
std::string ompl_ros_interface::PlannerConfig::config_ [private] |
Definition at line 107 of file ompl_ros_planner_config.h.
std::string ompl_ros_interface::PlannerConfig::description_ [private] |
Definition at line 106 of file ompl_ros_planner_config.h.
Definition at line 108 of file ompl_ros_planner_config.h.