Functions | |
bool | convertDoublesToEigen (const std::string &parent_name, std::vector< double > values, Eigen::Affine3d &transform) |
Convert from 6 doubles of [x,y,z] [r,p,y] to a transform. | |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value) |
Get a paremeter from the ROS param server. Note that does not provide for default values. | |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶ms_name, std::map< std::string, bool > ¶meters) |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, double &value) |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::vector< double > &values) |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, int &value) |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::size_t &value) |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::string &value) |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::vector< std::string > &values) |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, ros::Duration &value) |
bool | get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, Eigen::Affine3d &value) |
std::string | getDebugArrayString (std::vector< double > values) |
Output a string of values from an array for debugging. | |
std::string | getDebugArrayString (std::vector< std::string > values) |
void | shutdownIfError (const std::string &parent_name, std::size_t error_count) |
Check that there were no errors, and if there were, shutdown. |
bool rosparam_shortcuts::convertDoublesToEigen | ( | const std::string & | parent_name, |
std::vector< double > | values, | ||
Eigen::Affine3d & | transform | ||
) |
Convert from 6 doubles of [x,y,z] [r,p,y] to a transform.
Definition at line 256 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
bool & | value | ||
) |
Get a paremeter from the ROS param server. Note that does not provide for default values.
parent_name | - the name of the class that is calling this function, used for filtering out logging output by namespacing it |
nh | - a ROS node handle |
param_name | - name of parameter to get |
value | - resulting loaded values, or no change if error (function returns false) |
Definition at line 49 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | params_name, | ||
std::map< std::string, bool > & | parameters | ||
) |
Definition at line 64 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
double & | value | ||
) |
Definition at line 87 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
std::vector< double > & | values | ||
) |
Definition at line 102 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
int & | value | ||
) |
Definition at line 123 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
std::size_t & | value | ||
) |
Definition at line 138 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
std::string & | value | ||
) |
Definition at line 155 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
std::vector< std::string > & | values | ||
) |
Definition at line 170 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
ros::Duration & | value | ||
) |
Definition at line 191 of file rosparam_shortcuts.cpp.
bool rosparam_shortcuts::get | ( | const std::string & | parent_name, |
const ros::NodeHandle & | nh, | ||
const std::string & | param_name, | ||
Eigen::Affine3d & | value | ||
) |
Definition at line 210 of file rosparam_shortcuts.cpp.
std::string rosparam_shortcuts::getDebugArrayString | ( | std::vector< double > | values | ) |
Output a string of values from an array for debugging.
array | of values |
Definition at line 236 of file rosparam_shortcuts.cpp.
std::string rosparam_shortcuts::getDebugArrayString | ( | std::vector< std::string > | values | ) |
Definition at line 246 of file rosparam_shortcuts.cpp.
void rosparam_shortcuts::shutdownIfError | ( | const std::string & | parent_name, |
std::size_t | error_count | ||
) |
Check that there were no errors, and if there were, shutdown.
error | - total number of errors found |
Definition at line 275 of file rosparam_shortcuts.cpp.