XmlRpcConversion.hpp
Go to the documentation of this file.
00001 /*
00002  * XmlRpcConversion.hpp
00003  *
00004  *  Created on: Oct 20, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef XMLRPCCONVERSION_HPP_
00009 #define XMLRPCCONVERSION_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 #include <telekyb_defines/enum.hpp>
00014 
00015 //XmlRPC
00016 #include <XmlRpc.h>
00017 
00018 // ros
00019 #include <ros/console.h>
00020 
00021 // Eigen
00022 #include <Eigen/Dense>
00023 
00024 // Implementation of StringCoversion Classes
00025 namespace TELEKYB_NAMESPACE
00026 {
00027 // These all throw XmlRpc::XmlRpcException!
00028 
00029 template < class _T >
00030 void operator >> (const _T& input, XmlRpc::XmlRpcValue& output)
00031 {
00032         output = XmlRpc::XmlRpcValue(input);
00033 }
00034 
00035 template < class _T >
00036 void operator >> (XmlRpc::XmlRpcValue input, _T& output)
00037 {
00038         output = static_cast<_T>(input);
00039 }
00040 
00041 // Eigen::Matrix
00042 template<typename _Scalar, int _Rows, int _Cols, int _Options, int _MaxRows, int _MaxCols>
00043 void operator >> (const Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>& matrix, XmlRpc::XmlRpcValue& value)
00044 {
00045         int nValues = matrix.rows() * matrix.cols();
00046         value.setSize(nValues);
00047 
00048         for (int i = 0; i < nValues; ++i) {
00049                 value[i] = XmlRpc::XmlRpcValue( matrix(i / matrix.cols(), i % matrix.cols() ) );
00050         }
00051 
00052 }
00053 
00054 template<typename _Scalar, int _Rows, int _Cols, int _Options, int _MaxRows, int _MaxCols>
00055 void operator >> (XmlRpc::XmlRpcValue value, Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>& matrix)
00056 {
00057         int nValues = value.size();
00058 
00059         if (nValues == matrix.rows() * matrix.cols() ) {
00060                 // parse string into Matrix
00061                 for (int i = 0; i < matrix.rows(); i++) {
00062                         for (int j = 0; j < matrix.cols(); j++) {
00063                                 matrix(i, j) = static_cast<_Scalar>(value[i*matrix.cols() + j]);
00064                         }
00065                 }
00066         } else {
00067                 std::stringstream sstream;
00068                 sstream << "Unable to fill Eigen::Matrix. Input is of wrong size! Matrix(" <<
00069                                 matrix.rows() <<"x"<< matrix.cols() <<") != XmlRpcValue.size("<< nValues <<")";
00070                 throw XmlRpc::XmlRpcException(sstream.str());
00071         }
00072 }
00073 
00074 template<typename _Scalar, int _Options>
00075 void operator >> (const Eigen::Quaternion<_Scalar,_Options>& input, XmlRpc::XmlRpcValue& value)
00076 {
00077         value.setSize(4); // Quaterion has 4 Elements
00078 
00079         value[0] = XmlRpc::XmlRpcValue( input.w() );
00080         value[1] = XmlRpc::XmlRpcValue( input.x() );
00081         value[2] = XmlRpc::XmlRpcValue( input.y() );
00082         value[3] = XmlRpc::XmlRpcValue( input.z() );
00083 }
00084 
00085 template<typename _Scalar, int _Options>
00086 void operator >> (XmlRpc::XmlRpcValue input, Eigen::Quaternion<_Scalar,_Options>& quaternion)
00087 {
00088         if (input.size() != 4) {
00089                 std::stringstream sstream;
00090                 sstream << "Unable to fill Eigen::QuaternionBase< Eigen::Quaternion<_Scalar,_Options> >. "
00091                                 "Input is of wrong size! XmlRpcValue.size(" <<
00092                                 input.size() <<") != 4)";
00093                 throw XmlRpc::XmlRpcException(sstream.str());
00094         }
00095 
00096         // size is ok
00097         quaternion.w() = static_cast<_Scalar>(input[0]);
00098         quaternion.x() = static_cast<_Scalar>(input[1]);
00099         quaternion.y() = static_cast<_Scalar>(input[2]);
00100         quaternion.z() = static_cast<_Scalar>(input[3]);
00101 
00102 }
00103 
00104 // std::vector
00105 template<class _T>
00106 void operator >> (const std::vector<_T>& input, XmlRpc::XmlRpcValue& output)
00107 {
00108         output.setSize(input.size());
00109         for (size_t i = 0; i < input.size(); i++) {
00110                 input.at(i) >> output[i];
00111         }
00112 }
00113 
00114 template<class _T>
00115 void operator >> (XmlRpc::XmlRpcValue input, std::vector<_T>& output)
00116 {
00117         if (input.size() == (signed)output.size()) {
00118                 for (size_t i = 0; i < output.size(); i++) {
00119                         input[i] >> output[i];
00120                 }
00121         } else {
00122                 std::stringstream sstream;
00123                 sstream << "Unable to fill boost::array. Input is of wrong size! std::vector(" <<
00124                                 output.size() <<") != XmlRpcValue.size("<< input.size() <<")";
00125                 throw XmlRpc::XmlRpcException(sstream.str());
00126         }
00127         //output = static_cast<_T>(input);
00128 }
00129 
00130 // Boost Array
00131 template<class _T, std::size_t _N>
00132 void operator >> (const boost::array<_T,_N>& input, XmlRpc::XmlRpcValue& output)
00133 {
00134         output.setSize(_N);
00135         for (size_t i = 0; i < _N; i++) {
00136                 input.at(i) >> output[i];
00137         }
00138 }
00139 
00140 template<class _T, std::size_t _N>
00141 void operator >> (XmlRpc::XmlRpcValue input, boost::array<_T,_N>& output)
00142 {
00143         if (input.size() == _N) {
00144                 for (size_t i = 0; i < _N; i++) {
00145                         input[i] >> output[i];
00146                 }
00147         } else {
00148                 std::stringstream sstream;
00149                 sstream << "Unable to fill boost::array. Input is of wrong size! boost::array(" <<
00150                                 _N <<") != XmlRpcValue.size("<< input.size() <<")";
00151                 throw XmlRpc::XmlRpcException(sstream.str());
00152         }
00153         //output = static_cast<_T>(input);
00154 }
00155 
00156 // Enum
00157 template < class ENUM_, class TYPE_ >
00158 void operator >> (const boost::detail::enum_base<ENUM_, TYPE_>& input, XmlRpc::XmlRpcValue& output)
00159 {
00160         output = XmlRpc::XmlRpcValue( input.str() );
00161 }
00162 
00163 template < class ENUM_, class TYPE_ >
00164 void operator >> (XmlRpc::XmlRpcValue input, boost::detail::enum_base<ENUM_, TYPE_>& output)
00165 {
00166         std::string enumName = static_cast<std::string>(input);
00167         boost::optional<ENUM_> result = ENUM_::get_by_name(enumName.c_str());
00168         if (result) {
00169                 output = *result;
00170         } else {
00171                 std::string msg = std::string("Unknown enum ") + ENUM_::getEnumName() + "::" + enumName + "! Possible Values: " + ENUM_::getAllDomainNames(',') + ".";
00172                 throw XmlRpc::XmlRpcException(msg);
00173         }
00174 }
00175 
00176 }
00177 
00178 
00179 #endif /* XMLRPCCONVERSION_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


telekyb_base
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:12:34