Go to the documentation of this file.00001 #ifndef ETHERCAT_MANAGER_H
00002 #define ETHERCAT_MANAGER_H
00003
00004 #include <stdexcept>
00005 #include <string>
00006
00007 #include <stdint.h>
00008
00009 #include <boost/scoped_array.hpp>
00010 #include <boost/thread.hpp>
00011 #include <boost/thread/mutex.hpp>
00012
00013 namespace robotiq_ethercat
00014 {
00015
00020 class EtherCatError : public std::runtime_error
00021 {
00022 public:
00023 explicit EtherCatError(const std::string& what)
00024 : std::runtime_error(what)
00025 {}
00026 };
00027
00037 class EtherCatManager
00038 {
00039 public:
00049 EtherCatManager(const std::string& ifname);
00050
00051 ~EtherCatManager();
00052
00063 void write(int slave_no, uint8_t channel, uint8_t value);
00064
00071 uint8_t readInput(int slave_no, uint8_t channel) const;
00072
00079 uint8_t readOutput(int slave_no, uint8_t channel) const;
00080
00081 private:
00082 bool initSoem(const std::string& ifname);
00083
00084 const std::string ifname_;
00085 boost::scoped_array<uint8_t> iomap_;
00086 boost::thread cycle_thread_;
00087 mutable boost::mutex iomap_mutex_;
00088 bool stop_flag_;
00089 };
00090
00091 }
00092
00093 #endif