|
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] or 7 doubles of [x, y, z, qw, qx, qy, qz] to a transform. More...
|
|
bool | rosparam_shortcuts::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. More...
|
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶ms_name, std::map< std::string, bool > ¶meters) |
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, double &value) |
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::vector< double > &values) |
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, int &value) |
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::size_t &value) |
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::string &value) |
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::vector< std::string > &values) |
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, ros::Duration &value) |
|
bool | rosparam_shortcuts::get (const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, Eigen::Affine3d &value) |
|
std::string | rosparam_shortcuts::getDebugArrayString (std::vector< double > values) |
| Output a string of values from an array for debugging. More...
|
|
std::string | rosparam_shortcuts::getDebugArrayString (std::vector< std::string > values) |
|
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. More...
|
|