00001 /* 00002 * Copyright (c) 2016, 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 #pragma once 00025 00026 #include <ros_ethercat_hardware/ethercat_device.h> 00027 #include <realtime_tools/realtime_publisher.h> 00028 00029 #include <boost/ptr_container/ptr_vector.hpp> 00030 #include <boost/scoped_ptr.hpp> 00031 #include <vector> 00032 #include <queue> 00033 #include <string> 00034 #include "sr_ronex_msgs/DCMotorState.h" 00035 #include <dynamic_reconfigure/server.h> 00036 00037 #include <sr_ronex_external_protocol/Ronex_Protocol_0x02000009_DC_Motor_Small_00.h> 00038 00039 #include "sr_ronex_hardware_interface/DC_motor_small_hardware_interface.hpp" 00040 #include "sr_ronex_drivers/DCMotorConfig.h" 00041 00042 00043 class SrBoardDCMOTORSMALL : public EthercatDevice 00044 { 00045 public: 00046 virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address); 00047 virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed = true); 00048 00049 void dynamic_reconfigure_cb(sr_ronex_drivers::DCMotorConfig &config, uint32_t level); 00050 00051 SrBoardDCMOTORSMALL(); 00052 virtual ~SrBoardDCMOTORSMALL(); 00053 00054 protected: 00056 static const std::string product_alias_; 00057 00059 std::string ronex_id_; 00060 00061 string reason_; 00062 int level_; 00063 00064 int command_base_; 00065 int status_base_; 00066 00067 ros::NodeHandle node_; 00068 00069 ronex::DCMotor *dc_motor_small_; 00074 int16_t cycle_count_; 00075 00077 int32u digital_commands_; 00079 std::string device_name_; 00080 std::string serial_number_; 00081 00083 int device_offset_; 00084 00086 bool has_stacker_; 00087 00088 // Number of stacks present 00089 int stack; 00090 00091 std::vector<bool> input_mode_; 00092 00093 void packCommand(unsigned char *buffer, bool halt, bool reset); 00094 bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer); 00095 00096 void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer); 00097 00099 boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_ronex_msgs::DCMotorState> > state_publisher_; 00101 sr_ronex_msgs::DCMotorState state_msg_; 00102 00104 boost::scoped_ptr<dynamic_reconfigure::Server<sr_ronex_drivers::DCMotorConfig> > dynamic_reconfigure_server_; 00105 00106 dynamic_reconfigure::Server<sr_ronex_drivers::DCMotorConfig>::CallbackType function_cb_; 00107 00108 00110 void build_topics_(); 00111 00113 int parameter_id_; 00114 }; 00115 00116 /* For the emacs weenies in the crowd. 00117 Local Variables: 00118 c-basic-offset: 2 00119 End: 00120 */