wg_util.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #pragma once
00036 
00037 #include <stdint.h>
00038 #include "ethercat_hardware/ethercat_com.h"
00039 #include "ethercat_hardware/ethercat_device.h"
00040 
00041 namespace ethercat_hardware
00042 {
00043 
00044 // Syncmanger control register 0x804+N*8
00045 struct SyncManControl {
00046   union {
00047     uint8_t raw;
00048     struct {
00049       uint8_t mode            : 2;
00050       uint8_t direction       : 2;
00051       uint8_t ecat_irq_enable : 1;
00052       uint8_t pdi_irq_enable  : 1;
00053       uint8_t watchdog_enable : 1;
00054       uint8_t res1            : 1;
00055     } __attribute__ ((__packed__));      
00056   } __attribute__ ((__packed__));
00057   //static const unsigned BASE_ADDR=0x804;
00058   //static unsigned base_addr(unsigned num);
00059   //void print(std::ostream &os=std::cout) const;
00060 } __attribute__ ((__packed__));
00061 
00062 // Syncmanger status register 0x805+N*8
00063 struct SyncManStatus {
00064   union {
00065     uint8_t raw;
00066     struct {
00067       uint8_t interrupt_write : 1;
00068       uint8_t interrupt_read  : 1;
00069       uint8_t res1            : 1;
00070       uint8_t mailbox_status  : 1;
00071       uint8_t buffer_status   : 2;
00072       uint8_t res2            : 2;
00073     } __attribute__ ((__packed__));      
00074   } __attribute__ ((__packed__));
00075   //static const unsigned BASE_ADDR=0x805;
00076   //static unsigned base_addr(unsigned num);
00077   //void print(std::ostream &os=std::cout) const;
00078 } __attribute__ ((__packed__));
00079 
00080 // Syncmanger activation register 0x806+N*8
00081 struct SyncManActivate {
00082   union {
00083     uint8_t raw;
00084     struct {
00085       uint8_t enable : 1;
00086       uint8_t repeat_request : 1;
00087       uint8_t res4 : 4;
00088       uint8_t ecat_latch_event : 1;
00089       uint8_t pdi_latch_event : 1;
00090     } __attribute__ ((__packed__));      
00091   } __attribute__ ((__packed__));
00092   static const unsigned BASE_ADDR=0x806;
00093   static unsigned baseAddress(unsigned num);
00094   //void print(std::ostream &os=std::cout) const;  
00095   bool writeData(EthercatCom *com, EtherCAT_SlaveHandler *sh, EthercatDevice::AddrMode addrMode, unsigned num) const;
00096 } __attribute__ ((__packed__));
00097 
00098 // Syncmanger PDI control register 0x807+N*8
00099 struct SyncManPDIControl {
00100   union {
00101     uint8_t raw;
00102     struct {
00103       uint8_t deactivate : 1;
00104       uint8_t repeat_ack : 1;
00105       uint8_t res6 : 6;
00106     } __attribute__ ((__packed__));
00107   } __attribute__ ((__packed__));      
00108   //static const unsigned BASE_ADDR=0x807;
00109   //static unsigned base_addr(unsigned num);
00110   //void print(std::ostream &os=std::cout) const;
00111 } __attribute__ ((__packed__));
00112 
00113 
00114 // For SyncManager settings REG 0x800+8*N
00115 struct SyncMan {
00116   union {
00117     uint8_t raw[8];
00118     struct {
00119       uint16_t start_addr;
00120       uint16_t length;
00121       SyncManControl control;
00122       SyncManStatus status;
00123       SyncManActivate activate;
00124       SyncManPDIControl pdi_control;
00125     } __attribute__ ((__packed__));
00126   } __attribute__ ((__packed__));
00127   
00128   // Base address for first syncmanager
00129   static const unsigned BASE_ADDR=0x800;
00130   // Base address of Nth syncmanager for N=0-7
00131   static unsigned baseAddress(unsigned num);
00132   
00133   bool readData(EthercatCom *com, EtherCAT_SlaveHandler *sh, EthercatDevice::AddrMode addrMode, unsigned num);
00134   //void print(unsigned num, std::ostream &os=std::cout) const;
00135 } __attribute__ ((__packed__));
00136 
00137 namespace wg_util
00138 {
00139 unsigned computeChecksum(void const *data, unsigned length);
00140 unsigned int rotateRight8(unsigned in);
00141 };
00142 
00143 }; // end namespace ethercat_hardware


ethercat_hardware
Author(s): Rob Wheeler (email: wheeler@willowgarage.com), Maintained by Derek King (email: dking@willowgarage.com)
autogenerated on Thu Apr 24 2014 15:43:45