Go to the documentation of this file.
37 #ifndef XMLRPCHELPERS_H
38 #define XMLRPCHELPERS_H
62 std::ostringstream err_msg;
63 err_msg <<
"could not load parameter '" << param_name <<
"'. (namespace: "
68 output =
static_cast<T
>(val);
75 if(index >= col.
size())
77 std::ostringstream err_msg;
78 err_msg <<
"index '" << index <<
"' is over array capacity";
89 std::ostringstream err_msg;
90 err_msg <<
"could not find member '" << member <<
"'";
99 output =
static_cast<T
>(col[index]);
106 output =
static_cast<T
>(col[member]);
111 #endif // XMLRPCHELPERS_H
void fetchParam(ros::NodeHandle nh, const std::string ¶m_name, T &output)
void getStructMember(Struct &col, const std::string &member, T &output)
XmlRpc::XmlRpcValue Array
void checkArrayItem(const Array &col, int index)
XmlrpcHelperException(const std::string &what)
void getArrayItem(Array &col, int index, T &output)
void checkStructMember(const Struct &col, const std::string &member)
XmlRpc::XmlRpcValue Struct
const Type & getType() const
bool hasMember(const std::string &name) const
bool getParamCached(const std::string &key, bool &b) const
const std::string & getNamespace() const
Exception(const std::string &what)
twist_mux
Author(s): Enrique Fernandez
, Siegfried-A. Gevatter Pujals
autogenerated on Wed Oct 26 2022 02:18:09