Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H
00040 #define ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H
00041
00042
00043 #include <string>
00044 #include <vector>
00045 #include <map>
00046
00047
00048 #include <ros/ros.h>
00049
00050
00051 #include <Eigen/Geometry>
00052
00053
00054 #include <rosparam_shortcuts/deprecation.h>
00055
00056 namespace rosparam_shortcuts
00057 {
00058
00059
00060
00061
00071 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value);
00072
00073 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶ms_name,
00074 std::map<std::string, bool> ¶meters);
00075
00076 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, double &value);
00077
00078 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00079 std::vector<double> &values);
00080
00081 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, int &value);
00082
00083 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::size_t &value);
00084
00085 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::string &value);
00086
00087 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00088 std::vector<std::string> &values);
00089
00090 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00091 ros::Duration &value);
00092
00093 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00094 Eigen::Affine3d &value);
00095
00101 std::string getDebugArrayString(std::vector<double> values);
00102
00103 std::string getDebugArrayString(std::vector<std::string> values);
00104
00109 bool convertDoublesToEigen(const std::string &parent_name, std::vector<double> values, Eigen::Affine3d &transform);
00110
00115 void shutdownIfError(const std::string &parent_name, std::size_t error_count);
00116
00117 }
00118
00119 #endif // ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H