sr_board_adc16.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Shadow Robot Company, All rights reserved.
00003  *
00004  * This library is free software; you can redistribute it and/or
00005  * modify it under the terms of the GNU Lesser General Public
00006  * License as published by the Free Software Foundation; either
00007  * version 3.0 of the License, or (at your option) any later version.
00008  *
00009  * This library is distributed in the hope that it will be useful,
00010  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00011  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
00012  * Lesser General Public License for more details.
00013  *
00014  * You should have received a copy of the GNU Lesser General Public
00015  * License along with this library.
00016  */
00017 
00024 #ifndef _SR_BOARD_ADC16_HPP_
00025 #define _SR_BOARD_ADC16_HPP_
00026 
00027 #include <ros_ethercat_hardware/ethercat_device.h>
00028 #include <realtime_tools/realtime_publisher.h>
00029 #include <sr_ronex_msgs/ADC16State.h>
00030 
00031 #include <sr_ronex_external_protocol/Ronex_Protocol_0x02000008_ADC16_00.h>
00032 #include <sr_ronex_hardware_interface/adc16_hardware_interface.hpp>
00033 
00034 #include <boost/ptr_container/ptr_vector.hpp>
00035 #include <boost/scoped_ptr.hpp>
00036 #include <vector>
00037 #include <queue>
00038 #include <string>
00039 
00040 #include <dynamic_reconfigure/server.h>
00041 #include "sr_ronex_drivers/ADC16Config.h"
00042 
00043 
00044 class SrBoardADC16 : public EthercatDevice
00045 {
00046 public:
00047   virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address);
00048   virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed = true);
00049 
00050   SrBoardADC16();
00051   virtual ~SrBoardADC16();
00052 
00053   void dynamic_reconfigure_cb(sr_ronex_drivers::ADC16Config &config, uint32_t level);
00054 
00055 protected:
00057   static const std::string product_alias_;
00058 
00060   std::string ronex_id_;
00061 
00062   string reason_;
00063   int level_;
00064 
00065   int command_base_;
00066   int status_base_;
00067 
00068   ros::NodeHandle node_;
00069 
00071   ronex::ADC16 *adc16_;
00072 
00077   int16_t cycle_count_;
00078 
00080   int32u digital_commands_;
00081 
00083   std::string device_name_;
00084   std::string serial_number_;
00085 
00087   int device_offset_;
00088 
00089   // False if initial configuration has not been sent
00090   bool config_received_;
00091   // True if registers are being set
00092   bool reg_flag_;
00093   // Switch for states of setting registers
00094   int reg_state_;
00095   // Count for feedback
00096   int feedback_flag_;
00097 
00099   bool has_stacker_;
00100 
00102   std::vector<bool> input_mode_;
00103 
00104   // Queue of commands to send to register
00105   std::queue<RONEX_COMMAND_02000008> command_queue_;
00106   std::queue<RONEX_COMMAND_02000008> queue_backup_;
00107 
00108   // 1 for single ended adc, 2 for differential
00109   std::vector<int> pin_mode_;
00110 
00111   // Number of stacks present
00112   int stack;
00113 
00114   // values_s0: first single ended pin values,
00115   // values_s1: second single ended pin values,
00116   // values_d: differential pin values
00117   // fake_values: the additional bits sent
00118   // padded: the addition of requested and fake values
00119   std::vector<uint16_t> values_s0_;
00120   std::vector<uint16_t> values_s1_;
00121   std::vector<uint16_t> values_d_;
00122   std::vector<uint16_t> fake_values_s0_;
00123   std::vector<uint16_t> fake_values_s1_;
00124   std::vector<uint16_t> padded_s0_;
00125   std::vector<uint16_t> padded_s1_;
00126 
00127 
00128   void packCommand(unsigned char *buffer, bool halt, bool reset);
00129   bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer);
00130 
00131   void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer);
00132 
00134   boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_ronex_msgs::ADC16State> > state_publisher_;
00136   sr_ronex_msgs::ADC16State state_msg_;
00137 
00139   boost::scoped_ptr<dynamic_reconfigure::Server<sr_ronex_drivers::ADC16Config> > dynamic_reconfigure_server_;
00140 
00141   dynamic_reconfigure::Server<sr_ronex_drivers::ADC16Config>::CallbackType function_cb_;
00142 
00144   void build_topics_();
00145 
00147   int parameter_id_;
00148 };
00149 
00150 /* For the emacs weenies in the crowd.
00151    Local Variables:
00152    c-basic-offset: 2
00153    End:
00154 */
00155 
00156 #endif /* _SR_BOARD_ADC16_HPP_ */
00157 


sr_ronex_drivers
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless
autogenerated on Thu Jun 6 2019 21:22:00