riq_hand_command.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 #ifndef RIQ_HAND_ETHERCAT_HARDWARE__RIQ_HAND_COMMAND_H
00036 #define RIQ_HAND_ETHERCAT_HARDWARE__RIQ_HAND_COMMAND_H
00037 
00038 #include <stdint.h>
00039 
00040 namespace riq_hand_ethercat_hardware
00041 {
00042 
00043 
00044 struct RIQActionRequest
00045 {
00046   union {
00047     uint8_t raw_;
00048     struct {
00049       uint8_t initialize_    : 1;  
00050       uint8_t mode_          : 2;  
00051       uint8_t grip_          : 2;  
00052       uint8_t parital_open_  : 1;  
00053       uint8_t partial_close_ : 1;  
00054       uint8_t reserved       : 1;
00055       } __attribute__ ((__packed__));
00056     } __attribute__ ((__packed__));
00057 
00058   enum {CYLINDRICAL_MODE=0, PINCH_MODE=1, SPHERIOD_MODE=2, SCISSORS_MODE=3};
00059   enum {GRIP_STOP=0, GRIP_OPEN=1, GRIP_CLOSE=2, GRIP_STOP_X=3};
00060   enum {OPEN_MAX=0, OPEN_PARTIAL=1};
00061   enum {CLOSE_MAX=0, CLOSE_PARTIAL=1};
00062 
00063   static const char* modeString(unsigned mode);
00064   static const char* gripString(unsigned grip);
00065 
00066   const char* modeString() const {return modeString(mode_);}
00067   const char* gripString() const {return gripString(grip_);}
00068   
00069 } __attribute__ ((__packed__));  
00070 
00071 
00072 struct RIQSafetyShutdown
00073 {
00074   union {
00075     uint8_t raw_;
00076     struct {
00077       uint8_t reserved_    : 4;  
00078       uint8_t timeout_     : 4;
00079     } __attribute__ ((__packed__));
00080   } __attribute__ ((__packed__));
00081 
00082   enum {SHUTDOWN_TIMEOUT_NONE=0, 
00083         SHUTDOWN_TIMEOUT_20ms=1, 
00084         SHUTDOWN_TIMEOUT_40ms=2,
00085         SHUTDOWN_TIMEOUT_80ms=3,
00086         SHUTDOWN_TIMEOUT_160ms=4,
00087         SHUTDOWN_TIMEOUT_320ms=5,
00088         SHUTDOWN_TIMEOUT_640ms=6,
00089         SHUTDOWN_TIMEOUT_1280ms=7,
00090         SHUTDOWN_TIMEOUT_2560ms=8,
00091         SHUTDOWN_TIMEOUT_5120ms=9,
00092         SHUTDOWN_TIMEOUT_10240ms=10};
00093 } __attribute__ ((__packed__));
00094 
00095 
00096 
00097 struct RIQHandCommandEcat
00098 {
00099   RIQActionRequest action_request_;
00100   RIQSafetyShutdown safety_shutdown_; 
00101   uint8_t velocity_;
00102   uint8_t force_;
00103   uint8_t partial_open_;
00104   uint8_t partial_close_;
00105   uint8_t empty_[6];
00106 
00107   void zero();
00108 } __attribute__ ((__packed__));
00109 
00110 
00111 
00112 }; //namespace riq_hand_ethercat_hardware
00113 
00114 
00115 #endif /* RIQ_HAND_ETHERCAT_HARDWARE__RIQ_HAND_COMMAND_H */


riq_hand_ethercat_hardware
Author(s): Derek King
autogenerated on Tue Apr 22 2014 19:42:45