39 #ifndef ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H 40 #define ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H 51 #include <Eigen/Geometry> 71 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
bool &value);
73 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶ms_name,
74 std::map<std::string, bool> ¶meters);
76 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
double &value);
78 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
79 std::vector<double> &values);
81 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
int &value);
83 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name, std::size_t &value);
85 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name, std::string &value);
87 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
88 std::vector<std::string> &values);
90 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
93 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
94 Eigen::Affine3d &value);
109 bool convertDoublesToEigen(
const std::string &parent_name, std::vector<double> values, Eigen::Affine3d &transform);
115 void shutdownIfError(
const std::string &parent_name, std::size_t error_count);
119 #endif // ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H
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] or 7 doubles of [x, y, z, qw, qx, qy, qz] to a transform...
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
Check that there were no errors, and if there were, shutdown.
std::string getDebugArrayString(std::vector< double > values)
Output a string of values from an array for debugging.