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
00037 #ifndef XMLRPCHELPERS_H
00038 #define XMLRPCHELPERS_H
00039
00040 #include <sstream>
00041 #include <ros/ros.h>
00042
00043 namespace xh
00044 {
00045
00046 class XmlrpcHelperException : public ros::Exception
00047 {
00048 public:
00049 XmlrpcHelperException(const std::string& what)
00050 : ros::Exception(what) {}
00051 };
00052
00053 typedef XmlRpc::XmlRpcValue Struct;
00054 typedef XmlRpc::XmlRpcValue Array;
00055
00056 template <class T>
00057 void perform_cast(XmlRpc::XmlRpcValue val, T& output)
00058 {
00059 output = static_cast<T>(val);
00060 return;
00061 }
00062
00063
00064 template <>
00065 inline void perform_cast<double>(XmlRpc::XmlRpcValue val, double& output)
00066 {
00067 if (val.getType() == XmlRpc::XmlRpcValue::TypeInt)
00068 {
00069 output = static_cast<double>(static_cast<int>(val));
00070 }
00071 else
00072 {
00073 output = static_cast<double>(val);
00074 }
00075 }
00076
00077 template <class T>
00078 void fetchParam(ros::NodeHandle nh, const std::string& param_name, T& output)
00079 {
00080 XmlRpc::XmlRpcValue val;
00081 bool ok = false;
00082 try
00083 {
00084 ok = nh.getParamCached(param_name, val);
00085 }
00086 catch(const ros::InvalidNameException& e) {}
00087
00088 if (!ok)
00089 {
00090 std::ostringstream err_msg;
00091 err_msg << "could not load parameter '" << param_name << "'. (namespace: "
00092 << nh.getNamespace() << ")";
00093 throw XmlrpcHelperException(err_msg.str());
00094 }
00095
00096 perform_cast(val, output);
00097 }
00098
00099 inline void checkArrayItem(const Array& col, int index)
00100 {
00101 if (col.getType() != XmlRpc::XmlRpcValue::TypeArray)
00102 throw XmlrpcHelperException("not an array");
00103 if(index >= col.size())
00104 {
00105 std::ostringstream err_msg;
00106 err_msg << "index '" << index << "' is over array capacity";
00107 throw XmlrpcHelperException(err_msg.str());
00108 }
00109 }
00110
00111 inline void checkStructMember(const Struct& col, const std::string& member)
00112 {
00113 if (col.getType() != XmlRpc::XmlRpcValue::TypeStruct)
00114 throw XmlrpcHelperException("not a struct");
00115 if (!col.hasMember(member))
00116 {
00117 std::ostringstream err_msg;
00118 err_msg << "could not find member '" << member << "'";
00119 throw XmlrpcHelperException(err_msg.str());
00120 }
00121 }
00122
00123 template <class T>
00124 void getArrayItem(Array& col, int index, T& output)
00125 {
00126 checkArrayItem(col, index);
00127 perform_cast(col[index], output);
00128 }
00129
00130 template <class T>
00131 void getStructMember(Struct& col, const std::string& member, T& output)
00132 {
00133 checkStructMember(col, member);
00134 perform_cast(col[member], output);
00135 }
00136
00137 }
00138
00139 #endif