Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00021
00022
00023 #ifndef HELPER_H
00024 #define HELPER_H
00025
00026 #include <boost/shared_ptr.hpp>
00027 #include "CanOpenReceiveThread.h"
00028 #include "Logging.h"
00029
00030 namespace icl_hardware{
00031 namespace canopen_schunk{
00032
00033 typedef boost::shared_ptr<CanOpenReceiveThread> CanOpenReceiveThreadPtr;
00034 typedef boost::shared_ptr<icl_hardware::can::tCanDevice> CanDevPtr;
00035 typedef icl_hardware::can::tCanMessage CanMsg;
00036
00037
00044 std::string hexToString (const uint64_t num);
00045
00053 std::string hexArrayToString( const unsigned char* msg, const uint8_t length);
00054
00055 template <typename T>
00056 std::string binaryString (const T num)
00057 {
00058 const size_t T_size = sizeof(T) * 8;
00059 std::bitset<T_size> bs(num);
00060 std::stringstream ss;
00061 ss << "0b" << bs;
00062 return ss.str();
00063 }
00064
00074 std::string sanitizeString(const std::string& text);
00075
00076
00092 std::map<uint32_t, std::string> getErrorMapFromConfigFile(const std::string& filename,
00093 const std::string& category = "error_codes");
00094
00103 template <typename T>
00104 inline std::vector<uint8_t> convertToCharVector(const T value)
00105 {
00106 std::vector<uint8_t> out_vec;
00107 if (boost::is_fundamental<T>::value)
00108 {
00109 int32_t full_byte = 0xff;
00110 size_t num_bytes = sizeof(T);
00111 int32_t cast_int;
00112
00113 if ( num_bytes <= 4)
00114 {
00115 std::memcpy(&cast_int, &value, num_bytes);
00116 for (size_t i = 0; i < num_bytes; ++i)
00117 {
00118 int32_t unary = cast_int & full_byte;
00119 out_vec.push_back(static_cast<uint8_t>( unary >> i*8));
00120 full_byte = full_byte << 8;
00121 }
00122 }
00123 else
00124 {
00125 LOGGING_ERROR (CanOpen, "The given data is too large. The maximum datatype size is 4 bytes." << endl);
00126 throw std::bad_cast();
00127 }
00128 }
00129 else
00130 {
00131 LOGGING_ERROR (CanOpen, "Only fundamental datatypes can be casted with the help of " << "this function. Fundamental types include integral, floating point and void types." << endl);
00132 throw std::bad_cast();
00133 }
00134
00135 return out_vec;
00136 }
00137
00138
00146 template <typename T>
00147 inline T convertFromCharVector(const std::vector<uint8_t>& vec)
00148 {
00149 T ret_val = 0;
00150 size_t num_bytes = sizeof(T);
00151 if (boost::is_fundamental<T>::value && vec.size() == num_bytes)
00152 {
00153 std::memcpy(&ret_val, &vec[0], num_bytes);
00154 }
00155 else
00156 {
00157 LOGGING_ERROR (CanOpen, "Only fundamental datatypes can be casted with the help of " << "this function. Fundamental types include integral, floating point and void types." << endl);
00158 throw std::bad_cast();
00159 }
00160 return ret_val;
00161 }
00162
00163 }}
00164
00165 #endif // HELPER_H