ethercat_hardware.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef ETHERCAT_HARDWARE_H
36 #define ETHERCAT_HARDWARE_H
37 
39 
40 #include <al/ethercat_AL.h>
41 #include <al/ethercat_master.h>
42 #include <al/ethercat_slave_handler.h>
43 
47 
49 
50 #include <boost/accumulators/accumulators.hpp>
51 #include <boost/accumulators/statistics/stats.hpp>
52 #include <boost/accumulators/statistics/max.hpp>
53 #include <boost/accumulators/statistics/mean.hpp>
54 
55 #include <boost/thread/thread.hpp>
56 #include <boost/thread/mutex.hpp>
57 #include <boost/thread/condition_variable.hpp>
58 
59 #include <pluginlib/class_loader.h>
60 
61 #include <std_msgs/Bool.h>
62 
63 #include <boost/regex.hpp>
64 
65 using namespace boost::accumulators;
66 
68 {
70  void resetMaxTiming();
71  accumulator_set<double, stats<tag::max, tag::mean> > pack_command_acc_;
72  accumulator_set<double, stats<tag::max, tag::mean> > txandrx_acc_;
73  accumulator_set<double, stats<tag::max, tag::mean> > unpack_state_acc_;
74  accumulator_set<double, stats<tag::max, tag::mean> > publish_acc_;
76  double max_txandrx_;
78  double max_publish_;
80  unsigned device_count_;
81  bool pd_error_;
86  struct netif_counters counters_;
89  const char* motors_halted_reason_;
90 
91  static const bool collect_extra_timing_ = true;
92 };
93 
94 
109 {
110 public:
111 
114 
120  void initialize(const string &interface, unsigned int buffer_size,
121  const std::vector<boost::shared_ptr<EthercatDevice> > &slaves,
122  unsigned int num_ethercat_devices_,
123  unsigned timeout, unsigned max_pd_retries);
124 
132  void publish(const unsigned char *buffer, const EthercatHardwareDiagnostics &diagnostics);
133 
137  void stop();
138 
139 private:
140 
148  void publishDiagnostics();
149 
155  void diagnosticsThreadFunc();
156 
157 
161  static void timingInformation(
163  const string &key,
164  const accumulator_set<double, stats<tag::max, tag::mean> > &acc,
165  double max);
166 
168 
169  boost::mutex diagnostics_mutex_;
172  boost::thread diagnostics_thread_;
173 
175 
177  unsigned char *diagnostics_buffer_;
178  unsigned int buffer_size_;
179  std::vector<boost::shared_ptr<EthercatDevice> > slaves_;
180  unsigned int num_ethercat_devices_;
181  string interface_;
182 
184  unsigned timeout_;
186  unsigned max_pd_retries_;
187 
193  static const unsigned dropped_packet_warning_hold_time_ = 10; //keep warning up for 10 seconds
194 
195  diagnostic_msgs::DiagnosticArray diagnostic_array_;
198  vector<diagnostic_msgs::KeyValue> values_;
200 };
201 
202 
204 {
205 public:
209  EthercatHardware(const std::string& name);
210 
214  ~EthercatHardware();
215 
221  void update(bool reset, bool halt);
222 
228  void init(char *interface, bool allow_unprogrammed);
229 
233  void collectDiagnostics();
234 
235  void printCounters(std::ostream &os=std::cout);
236 
240  bool txandrx_PD(unsigned buffer_size, unsigned char* buffer, unsigned tries);
241 
251  bool publishTrace(int position, const string &reason, unsigned level, unsigned delay);
252 
254 
255 private:
256  static void changeState(EtherCAT_SlaveHandler *sh, EC_State new_state);
257 
258  void loadNonEthercatDevices();
259  boost::shared_ptr<EthercatDevice> configNonEthercatDevice(const std::string &product_id, const std::string &data);
260 
261  void haltMotors(bool error, const char* reason);
262 
264 
265  struct netif *ni_;
266  string interface_;
267 
268  EtherCAT_AL *al_;
269  EtherCAT_Master *em_;
270 
271  boost::shared_ptr<EthercatDevice> configSlave(EtherCAT_SlaveHandler *sh);
272  std::vector<boost::shared_ptr<EthercatDevice> > slaves_;
273  unsigned int num_ethercat_devices_;
274 
275  unsigned char *this_buffer_;
276  unsigned char *prev_buffer_;
277  unsigned char *buffers_;
278  unsigned int buffer_size_;
279 
281  unsigned int reset_state_;
282 
283  unsigned timeout_;
284  unsigned max_pd_retries_;
285 
286  void publishDiagnostics();
287  static void updateAccMax(double &max, const accumulator_set<double, stats<tag::max, tag::mean> > &acc);
292 
294 
296 
298 };
299 
300 #endif /* ETHERCAT_HARDWARE_H */
vector< diagnostic_msgs::KeyValue > values_
unsigned reset_motors_service_count_
Number of times reset_motor service has been used.
EthercatHardwareDiagnostics diagnostics_
Diagnostics information use by publish function.
EtherCAT_Master * em_
ROSCONSOLE_DECL void initialize()
pr2_hardware_interface::HardwareInterface * hw_
Publishes EthercatHardware diagnostics.
std::vector< boost::shared_ptr< EthercatDevice > > slaves_
struct netif * ni_
accumulator_set< double, stats< tag::max, tag::mean > > pack_command_acc_
time taken by all devices packCommand functions
unsigned halt_motors_service_count_
Number of time halt_motor service call is used.
unsigned halt_motors_error_count_
Number of transitions into halt state due to device error.
pluginlib::ClassLoader< EthercatDevice > device_loader_
ros::NodeHandle node_
bool motors_halted_
True if motors are halted.
unsigned char * prev_buffer_
EthernetInterfaceInfo ethernet_interface_info_
Information about Ethernet interface used for EtherCAT communication.
accumulator_set< double, stats< tag::max, tag::mean > > txandrx_acc_
time taken by to transmit and recieve process data
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
const char * motors_halted_reason_
reason that motors first halted
unsigned timeout_
Timeout (in microseconds) to used for sending/recieving packets once in realtime mode.
unsigned int buffer_size_
uint16_t status
std::vector< boost::shared_ptr< EthercatDevice > > slaves_
uint64_t last_dropped_packet_count_
Count of dropped packets last diagnostics cycle.
EthercatHardwareDiagnostics diagnostics_
unsigned int reset_state_
unsigned char * buffers_
diagnostic_updater::DiagnosticStatusWrapper status_
unsigned int num_ethercat_devices_
realtime_tools::RealtimePublisher< std_msgs::Bool > motor_publisher_
boost::condition_variable diagnostics_cond_
EthercatOobCom * oob_com_
unsigned char * this_buffer_
diagnostic_msgs::DiagnosticArray diagnostic_array_
EthercatHardwareDiagnosticsPublisher diagnostics_publisher_
unsigned timeout_
Timeout controls how long EtherCAT driver waits for packet before declaring it as dropped...
unsigned max_pd_retries_
Number of times (in a row) to retry sending process data (realtime data) before halting motors...
boost::mutex diagnostics_mutex_
mutex protects all class data and cond variable
accumulator_set< double, stats< tag::max, tag::mean > > unpack_state_acc_
time taken by all devices updateState functions
unsigned max_pd_retries_
Max number of times to retry sending process data before halting motors.
bool halt_after_reset_
True if motor halt soon after motor reset.
ros::Time last_dropped_packet_time_
Time last packet was dropped 0 otherwise. Used for warning about dropped packets. ...
void init(char *interface)
Definition: motorconf.cpp:88
accumulator_set< double, stats< tag::max, tag::mean > > publish_acc_
time taken by any publishing step in main loop


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Fri Mar 15 2019 02:53:29