$search
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_H 00036 #define ETHERCAT_HARDWARE_H 00037 00038 #include <pr2_hardware_interface/hardware_interface.h> 00039 00040 #include <al/ethercat_AL.h> 00041 #include <al/ethercat_master.h> 00042 #include <al/ethercat_slave_handler.h> 00043 00044 #include "ethercat_hardware/ethercat_device.h" 00045 #include "ethercat_hardware/ethercat_com.h" 00046 #include "ethercat_hardware/ethernet_interface_info.h" 00047 00048 #include <realtime_tools/realtime_publisher.h> 00049 00050 #include <boost/accumulators/accumulators.hpp> 00051 #include <boost/accumulators/statistics/stats.hpp> 00052 #include <boost/accumulators/statistics/max.hpp> 00053 #include <boost/accumulators/statistics/mean.hpp> 00054 00055 #include <boost/thread/thread.hpp> 00056 #include <boost/thread/mutex.hpp> 00057 #include <boost/thread/condition_variable.hpp> 00058 00059 #include <pluginlib/class_loader.h> 00060 00061 #include <std_msgs/Bool.h> 00062 00063 #include <boost/regex.hpp> 00064 00065 using namespace boost::accumulators; 00066 00067 struct EthercatHardwareDiagnostics 00068 { 00069 EthercatHardwareDiagnostics(); 00070 void resetMaxTiming(); 00071 accumulator_set<double, stats<tag::max, tag::mean> > pack_command_acc_; 00072 accumulator_set<double, stats<tag::max, tag::mean> > txandrx_acc_; 00073 accumulator_set<double, stats<tag::max, tag::mean> > unpack_state_acc_; 00074 accumulator_set<double, stats<tag::max, tag::mean> > publish_acc_; 00075 double max_pack_command_; 00076 double max_txandrx_; 00077 double max_unpack_state_; 00078 double max_publish_; 00079 int txandrx_errors_; 00080 unsigned device_count_; 00081 bool pd_error_; 00082 bool halt_after_reset_; 00083 unsigned reset_motors_service_count_; 00084 unsigned halt_motors_service_count_; 00085 unsigned halt_motors_error_count_; 00086 struct netif_counters counters_; 00087 bool input_thread_is_stopped_; 00088 bool motors_halted_; 00089 00090 static const bool collect_extra_timing_ = true; 00091 }; 00092 00093 00107 class EthercatHardwareDiagnosticsPublisher 00108 { 00109 public: 00110 00111 EthercatHardwareDiagnosticsPublisher(ros::NodeHandle &node); 00112 ~EthercatHardwareDiagnosticsPublisher(); 00113 00119 void initialize(const string &interface, unsigned int buffer_size, 00120 const std::vector<EthercatDevice*> &slaves, 00121 unsigned int num_ethercat_devices_, 00122 unsigned timeout, unsigned max_pd_retries); 00123 00131 void publish(const unsigned char *buffer, const EthercatHardwareDiagnostics &diagnostics); 00132 00136 void stop(); 00137 00138 private: 00139 00147 void publishDiagnostics(); 00148 00154 void diagnosticsThreadFunc(); 00155 00156 00160 static void timingInformation( 00161 diagnostic_updater::DiagnosticStatusWrapper &status, 00162 const string &key, 00163 const accumulator_set<double, stats<tag::max, tag::mean> > &acc, 00164 double max); 00165 00166 ros::NodeHandle node_; 00167 00168 boost::mutex diagnostics_mutex_; 00169 boost::condition_variable diagnostics_cond_; 00170 bool diagnostics_ready_; 00171 boost::thread diagnostics_thread_; 00172 00173 ros::Publisher publisher_; 00174 00175 EthercatHardwareDiagnostics diagnostics_; 00176 unsigned char *diagnostics_buffer_; 00177 unsigned int buffer_size_; 00178 std::vector<EthercatDevice*> slaves_; 00179 unsigned int num_ethercat_devices_; 00180 string interface_; 00181 00183 unsigned timeout_; 00185 unsigned max_pd_retries_; 00186 00188 uint64_t last_dropped_packet_count_; 00190 ros::Time last_dropped_packet_time_; 00192 static const unsigned dropped_packet_warning_hold_time_ = 10; //keep warning up for 10 seconds 00193 00194 diagnostic_msgs::DiagnosticArray diagnostic_array_; 00196 EthernetInterfaceInfo ethernet_interface_info_; 00197 vector<diagnostic_msgs::KeyValue> values_; 00198 diagnostic_updater::DiagnosticStatusWrapper status_; 00199 }; 00200 00201 00202 class EthercatHardware 00203 { 00204 public: 00208 EthercatHardware(const std::string& name); 00209 00213 ~EthercatHardware(); 00214 00220 void update(bool reset, bool halt); 00221 00227 void init(char *interface, bool allow_unprogrammed); 00228 00232 void collectDiagnostics(); 00233 00234 void printCounters(std::ostream &os=std::cout); 00235 00239 bool txandrx_PD(unsigned buffer_size, unsigned char* buffer, unsigned tries); 00240 00250 bool publishTrace(int position, const string &reason, unsigned level, unsigned delay); 00251 00252 pr2_hardware_interface::HardwareInterface *hw_; 00253 00254 private: 00255 static void changeState(EtherCAT_SlaveHandler *sh, EC_State new_state); 00256 00257 void loadNonEthercatDevices(); 00258 EthercatDevice *configNonEthercatDevice(const std::string &product_id, const std::string &data); 00259 00260 ros::NodeHandle node_; 00261 00262 struct netif *ni_; 00263 string interface_; 00264 00265 EtherCAT_AL *al_; 00266 EtherCAT_Master *em_; 00267 00268 EthercatDevice *configSlave(EtherCAT_SlaveHandler *sh); 00269 std::vector<EthercatDevice*> slaves_; 00270 unsigned int num_ethercat_devices_; 00271 00272 unsigned char *this_buffer_; 00273 unsigned char *prev_buffer_; 00274 unsigned char *buffers_; 00275 unsigned int buffer_size_; 00276 00277 bool halt_motors_; 00278 unsigned int reset_state_; 00279 00280 unsigned timeout_; 00281 unsigned max_pd_retries_; 00282 00283 void publishDiagnostics(); 00284 static void updateAccMax(double &max, const accumulator_set<double, stats<tag::max, tag::mean> > &acc); 00285 EthercatHardwareDiagnostics diagnostics_; 00286 EthercatHardwareDiagnosticsPublisher diagnostics_publisher_; 00287 ros::Time last_published_; 00288 ros::Time last_reset_; 00289 00290 realtime_tools::RealtimePublisher<std_msgs::Bool> motor_publisher_; 00291 ros::Time motor_last_published_; 00292 00293 EthercatOobCom *oob_com_; 00294 00295 pluginlib::ClassLoader<EthercatDevice> device_loader_; 00296 }; 00297 00298 #endif /* ETHERCAT_HARDWARE_H */