wg021.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 ETHERCAT_HARDWARE_WG021_H
00036 #define ETHERCAT_HARDWARE_WG021_H
00037 
00038 #include <ethercat_hardware/wg0x.h>
00039 
00040 
00041 struct WG021Status
00042 {
00043   uint8_t mode_;
00044   uint8_t digital_out_;
00045   uint8_t general_config_;
00046   uint8_t pad1_;
00047   int16_t programmed_current_;
00048   int16_t measured_current_;
00049   uint32_t timestamp_;
00050   uint8_t config0_;
00051   uint8_t config1_;
00052   uint8_t config2_;
00053   uint8_t pad2_;
00054   uint32_t pad3_;
00055   uint16_t pad4_;
00056   uint8_t pad5_;
00057   uint8_t output_status_;
00058   uint32_t output_start_timestamp_;
00059   uint32_t output_stop_timestamp_;
00060   uint16_t board_temperature_;
00061   uint16_t bridge_temperature_;
00062   uint16_t supply_voltage_;
00063   int16_t led_voltage_;
00064   uint16_t packet_count_;
00065   uint8_t pad_;
00066   uint8_t checksum_;
00067   static const unsigned SIZE=44;
00068 }__attribute__ ((__packed__));
00069 
00070 struct WG021Command
00071 {
00072   uint8_t mode_;
00073   uint8_t digital_out_;
00074   uint8_t general_config_;
00075   uint8_t pad1_;
00076   int16_t programmed_current_;
00077   int16_t pad2_;
00078   int32_t pad3_;
00079   uint8_t config0_;
00080   uint8_t config1_;
00081   uint8_t config2_;
00082   uint8_t checksum_;
00083 }__attribute__ ((__packed__));
00084 
00085 class WG021 : public WG0X
00086 {
00087 public:
00088   WG021() : projector_(digital_out_A_, digital_out_B_, digital_out_I_, digital_out_M_, digital_out_L0_, digital_out_L1_) {}
00089   void construct(EtherCAT_SlaveHandler *sh, int &start_address);
00090   int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true);
00091   void packCommand(unsigned char *buffer, bool halt, bool reset);
00092   bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer);
00093   void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *);
00094   enum
00095   {
00096     PRODUCT_CODE = 6805021
00097   };
00098   enum
00099   {
00100     PROJECTOR_CONFIG_ENABLE = 8,
00101     PROJECTOR_CONFIG_ENABLE_ENABLED = 8,
00102     PROJECTOR_CONFIG_ENABLE_DISABLED = 0,
00103 
00104     PROJECTOR_CONFIG_ACTION = 4,
00105     PROJECTOR_CONFIG_ACTION_ON = 4,
00106     PROJECTOR_CONFIG_ACTION_OFF = 0,
00107 
00108     PROJECTOR_CONFIG_POLARITY = 2,
00109     PROJECTOR_CONFIG_POLARITY_ACTIVE_HIGH = 2,
00110     PROJECTOR_CONFIG_POLARITY_ACTIVE_LOW = 0,
00111 
00112     PROJECTOR_CONFIG_STATE = 1,
00113     PROJECTOR_CONFIG_STATE_HIGH = 1,
00114     PROJECTOR_CONFIG_STATE_LOW = 0
00115   };
00116 private:
00117   pr2_hardware_interface::DigitalOut digital_out_A_;
00118   pr2_hardware_interface::DigitalOut digital_out_B_;
00119   pr2_hardware_interface::DigitalOut digital_out_I_;
00120   pr2_hardware_interface::DigitalOut digital_out_M_;
00121   pr2_hardware_interface::DigitalOut digital_out_L0_;
00122   pr2_hardware_interface::DigitalOut digital_out_L1_;
00123   pr2_hardware_interface::Projector projector_;
00124 };
00125 
00126 #endif /* ETHERCAT_HARDWARE_WG021_H */


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