Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00023
00024
00025 #ifndef DS301NODE_H
00026 #define DS301NODE_H
00027
00028
00029 #include "NMT.h"
00030 #include "RPDO.h"
00031 #include "TPDO.h"
00032 #include "SDO.h"
00033 #include "EMCY.h"
00034 #include "HeartBeatMonitor.h"
00035
00036 #include "helper.h"
00037 #include "Logging.h"
00038 #include "exceptions.h"
00039
00040 #include <boost/unordered_map.hpp>
00041
00042 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
00043
00044 #include <icl_comm_websocket/WsBroadcaster.h>
00045 #else
00046
00047
00048
00049
00050 namespace icl_comm{
00051 namespace websocket{
00052 class WsBroadcaster;
00053 }}
00054 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
00055
00056
00057 namespace icl_hardware {
00058 namespace canopen_schunk {
00059
00067 class DS301Node
00068 {
00069 public:
00078 struct PDOMapEntry
00079 {
00080 uint16_t pdo_nr;
00081 uint8_t pdo_mapping_index;
00082 };
00083
00088 enum ePDO_TYPE
00089 {
00090 RECEIVE_PDO,
00091 TRANSMIT_PDO
00092 };
00093
00095 typedef boost::shared_ptr<DS301Node> Ptr;
00097 typedef boost::shared_ptr<const DS301Node> ConstPtr;
00098
00099 DS301Node(const uint8_t node_id, const CanDevPtr& can_device, HeartBeatMonitor::Ptr heartbeat_monitor);
00100
00101 uint8_t getNodeId() const {return m_node_id;}
00102
00103
00107 virtual void initNode();
00108
00112 virtual void registerWSBroadcaster(boost::shared_ptr<icl_comm::websocket::WsBroadcaster> broadcaster);
00113
00118 virtual void startHeartbeat();
00119
00135 virtual void initPDOMappingSingle (const PDO::MappingConfigurationList& config,
00136 const uint16_t pdo_nr,
00137 const PDO::eTransmissionType& transmission_type,
00138 const ePDO_TYPE& pdo_type,
00139 const bool dummy_mapping = false,
00140 const uint8_t cyclic_timeout_cycles = 0);
00141
00157 virtual void appendPDOMappingSingle (const PDO::MappingConfigurationList& config,
00158 const uint16_t pdo_nr,
00159 const PDO::eTransmissionType& transmission_type,
00160 const ePDO_TYPE& pdo_type,
00161 const bool dummy_mapping = false,
00162 const uint8_t cyclic_timeout_cycles = 0);
00163
00164 template <typename T>
00165 T getRPDOValue (const std::string& identifier)
00166 {
00167
00168 if (m_rpdo_mapping.find(identifier) == m_rpdo_mapping.end())
00169 {
00170 std::stringstream ss;
00171 ss << "Could not find RPDO entry identifier string " << identifier << ". Aborting action now. ";
00172 throw PDOException(ss.str());
00173 }
00174 const PDOMapEntry& entry = m_rpdo_mapping[identifier];
00175
00176 const PDO::Mapping& mapping = m_rpdos[entry.pdo_nr]->m_mapping_list[entry.pdo_mapping_index];
00177
00178
00179 return convertFromCharVector<T>(mapping.data);
00180 }
00181
00189 template <typename T>
00190 T getTPDOValue (const std::string& identifier)
00191 {
00192
00193 if (m_tpdo_mapping.find(identifier) == m_tpdo_mapping.end())
00194 {
00195 std::stringstream ss;
00196 ss << "Could not find TPDO entry identifier string " << identifier << ". Aborting action now. ";
00197 throw PDOException(ss.str());
00198 }
00199 const PDOMapEntry& entry = m_tpdo_mapping[identifier];
00200
00201 const PDO::Mapping& mapping = m_tpdos[entry.pdo_nr]->m_mapping_list[entry.pdo_mapping_index];
00202
00203
00204 return convertFromCharVector<T>(mapping.data);
00205 }
00206
00214 template <typename T>
00215 bool setRPDOValue (const std::string& identifier, const T value)
00216 {
00217
00218 if (m_rpdo_mapping.find(identifier) == m_rpdo_mapping.end())
00219 {
00220 std::stringstream ss;
00221 ss << "Could not find RPDO entry identifier string " << identifier << ". Aborting action now. ";
00222 throw PDOException(ss.str());
00223 }
00224 const PDOMapEntry& entry = m_rpdo_mapping[identifier];
00225 PDO::Mapping& mapping = m_rpdos[entry.pdo_nr]->m_mapping_list[entry.pdo_mapping_index];
00226
00227 if (sizeof(T) == mapping.data.size())
00228 {
00229 std::memcpy(&(mapping.data[0]), &value, sizeof(T));
00230 }
00231
00232 LOGGING_TRACE (CanOpen, "Setting " << identifier << " for node " << m_node_id << " to " << value << endl);
00233
00234 return true;
00235 }
00236
00245 template <typename T>
00246 bool setTPDOValue (const std::string& identifier, const T value)
00247 {
00248
00249 if (m_tpdo_mapping.find(identifier) == m_tpdo_mapping.end())
00250 {
00251 std::stringstream ss;
00252 ss << "Could not find TPDO entry identifier string " << identifier << ". Aborting action now. ";
00253 throw PDOException(ss.str());
00254 }
00255 const PDOMapEntry& entry = m_tpdo_mapping[identifier];
00256 PDO::Mapping& mapping = m_tpdos[entry.pdo_nr]->m_mapping_list[entry.pdo_mapping_index];
00257
00258 if (sizeof(T) == mapping.data.size())
00259 {
00260 std::memcpy(&(mapping.data[0]), &value, sizeof(T));
00261 }
00262
00263 LOGGING_TRACE (CanOpen, "Setting " << identifier << " for node " << m_node_id << " to " << value << endl);
00264
00265 return true;
00266 }
00267
00271 void uploadPDOs ();
00272
00276 void downloadPDOs ();
00277
00281 void printPDOMapping();
00282
00295 void registerPDONotifyCallback (const std::string& identifier, const boost::function<void ()>& f );
00296
00300 virtual void stopNode();
00301
00303 NMT m_nmt;
00305 SDO m_sdo;
00307 RPDO::PtrList m_rpdos;
00309 TPDO::PtrList m_tpdos;
00311 EMCY::Ptr m_emcy;
00312
00313 protected:
00315 uint8_t m_node_id;
00316
00318 CanDevPtr m_can_dev;
00319
00321 boost::unordered_map<std::string, PDOMapEntry> m_rpdo_mapping;
00322
00324 boost::unordered_map<std::string, PDOMapEntry> m_tpdo_mapping;
00325
00326 HeartBeatMonitor::Ptr m_heartbeat_monitor;
00327
00328 uint16_t m_heartbeat_cycle_time_ms;
00329
00331 boost::shared_ptr<icl_comm::websocket::WsBroadcaster> m_ws_broadcaster;
00332
00333 };
00334
00335 }}
00336
00337 #endif // DS301NODE_H