ethercat_manager.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2015, Jonathan Meyer
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Tokyo Opensource Robotics Kyokai Association. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 // copied from https://github.com/ros-industrial/robotiq/blob/jade-devel/robotiq_ethercat/src/ethercat_manager.cpp
00029 
00030 #ifndef ETHERCAT_MANAGER_H
00031 #define ETHERCAT_MANAGER_H
00032 
00033 #include <stdexcept>
00034 #include <string>
00035 
00036 #include <stdint.h>
00037 
00038 #include <boost/scoped_array.hpp>
00039 #include <boost/thread.hpp>
00040 #include <boost/thread/mutex.hpp>
00041 
00042 namespace ethercat {
00043 
00048 class EtherCatError : public std::runtime_error
00049 {
00050 public:
00051   explicit EtherCatError(const std::string& what)
00052     : std::runtime_error(what)
00053   {}
00054 };
00055 
00065 class EtherCatManager
00066 {
00067 public:
00077   EtherCatManager(const std::string& ifname);
00078   
00079   ~EtherCatManager();
00080 
00091   void write(int slave_no, uint8_t channel, uint8_t value);
00092 
00099   uint8_t readInput(int slave_no, uint8_t channel) const;
00100 
00107   uint8_t readOutput(int slave_no, uint8_t channel) const;
00108 
00117   template <typename T>
00118   uint8_t writeSDO(int slave_no, uint16_t index, uint8_t subidx, T value) const;
00119 
00127   template <typename T>
00128   T readSDO(int slave_no, uint16_t index, uint8_t subidx) const;
00129 
00133   int getNumClinets() const;
00134 
00138   void getStatus(int slave_no, std::string &name, int &eep_man, int &eep_id, int &eep_rev, int &obits, int &ibits, int &state, int &pdelay, int &hasdc, int &activeports, int &configadr) const;
00139 
00140 private:
00141   bool initSoem(const std::string& ifname);
00142 
00143   const std::string ifname_;
00144   uint8_t iomap_[4096];
00145   int num_clients_;
00146   boost::thread cycle_thread_;
00147   mutable boost::mutex iomap_mutex_;
00148   bool stop_flag_;
00149 };
00150 
00151 }
00152 
00153 #endif
00154 


ethercat_manager
Author(s): Jonathan Meyer
autogenerated on Sat Jun 8 2019 19:23:26