netft_rdt_driver.cpp
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 #include "netft_rdt_driver.h"
36 #include <stdint.h>
37 #include <exception>
38 
39 using boost::asio::ip::udp;
40 
41 namespace netft_rdt_driver
42 {
43 
44 struct RDTRecord
45 {
46  uint32_t rdt_sequence_;
47  uint32_t ft_sequence_;
48  uint32_t status_;
49  int32_t fx_;
50  int32_t fy_;
51  int32_t fz_;
52  int32_t tx_;
53  int32_t ty_;
54  int32_t tz_;
55 
56  enum {RDT_RECORD_SIZE = 36};
57  void unpack(const uint8_t *buffer);
58  static uint32_t unpack32(const uint8_t *buffer);
59 };
60 
61 uint32_t RDTRecord::unpack32(const uint8_t *buffer)
62 {
63  return
64  ( uint32_t(buffer[0]) << 24) |
65  ( uint32_t(buffer[1]) << 16) |
66  ( uint32_t(buffer[2]) << 8 ) |
67  ( uint32_t(buffer[3]) << 0 ) ;
68 }
69 
70 void RDTRecord::unpack(const uint8_t *buffer)
71 {
72  rdt_sequence_ = unpack32(buffer + 0);
73  ft_sequence_ = unpack32(buffer + 4);
74  status_ = unpack32(buffer + 8);
75  fx_ = unpack32(buffer + 12);
76  fy_ = unpack32(buffer + 16);
77  fz_ = unpack32(buffer + 20);
78  tx_ = unpack32(buffer + 24);
79  ty_ = unpack32(buffer + 28);
80  tz_ = unpack32(buffer + 32);
81 }
82 
83 
84 struct RDTCommand
85 {
86  uint16_t command_header_;
87  uint16_t command_;
88  uint32_t sample_count_;
89 
90  RDTCommand() : command_header_(HEADER)
91  {
92  // empty
93  }
94 
95  enum {HEADER=0x1234};
96 
97  // Possible values for command_
98  enum {
99  CMD_STOP_STREAMING=0,
100  CMD_START_HIGH_SPEED_STREAMING=2,
101  // More command values are available but are not used by this driver
102  };
103 
104  // Special values for sample count
105  enum { INFINITE_SAMPLES=0 };
106 
107  enum {RDT_COMMAND_SIZE = 8};
108 
110  // Buffer should be RDT_COMMAND_SIZE
111  void pack(uint8_t *buffer) const;
112 };
113 
114 void RDTCommand::pack(uint8_t *buffer) const
115 {
116  // Data is big-endian
117  buffer[0] = (command_header_ >> 8) & 0xFF;
118  buffer[1] = (command_header_ >> 0) & 0xFF;
119  buffer[2] = (command_ >> 8) & 0xFF;
120  buffer[3] = (command_ >> 0) & 0xFF;
121  buffer[4] = (sample_count_ >> 8) & 0xFF;
122  buffer[5] = (sample_count_ >> 0) & 0xFF;
123  buffer[6] = (sample_count_ >> 8) & 0xFF;
124  buffer[7] = (sample_count_ >> 0) & 0xFF;
125 }
126 
127 
128 NetFTRDTDriver::NetFTRDTDriver(const std::string &address) :
129  address_(address),
130  socket_(io_service_),
131  stop_recv_thread_(false),
132  recv_thread_running_(false),
133  packet_count_(0),
134  lost_packets_(0),
135  out_of_order_count_(0),
136  seq_counter_(0),
137  diag_packet_count_(0),
138  last_diag_pub_time_(ros::Time::now()),
139  last_rdt_sequence_(0),
140  system_status_(0)
141 {
142  // Construct UDP socket
143  udp::endpoint netft_endpoint( boost::asio::ip::address_v4::from_string(address), RDT_PORT);
144  socket_.open(udp::v4());
145  socket_.connect(netft_endpoint);
146 
147  // TODO : Get/Set Force/Torque scale for device
148  // Force/Sclae is based on counts per force/torque value from device
149  // these value are manually read from device webserver, but in future they
150  // may be collected using http get requests
151  static const double counts_per_force = 1000000;
152  static const double counts_per_torque = 1000000;
153  force_scale_ = 1.0 / counts_per_force;
154  torque_scale_ = 1.0 / counts_per_torque;
155 
156  // Start receive thread
157  recv_thread_ = boost::thread(&NetFTRDTDriver::recvThreadFunc, this);
158 
159  // Since start steaming command is sent with UDP packet,
160  // the packet could be lost, retry startup 10 times before giving up
161  for (int i=0; i<10; ++i)
162  {
163  startStreaming();
164  if (waitForNewData())
165  break;
166  }
167  { boost::unique_lock<boost::mutex> lock(mutex_);
168  if (packet_count_ == 0)
169  {
170  throw std::runtime_error("No data received from NetFT device");
171  }
172  }
173 
174 }
175 
176 
178 {
179  // TODO stop transmission,
180  // stop thread
181  stop_recv_thread_ = true;
182  if (!recv_thread_.timed_join(boost::posix_time::time_duration(0,0,1,0)))
183  {
184  ROS_WARN("Interrupting recv thread");
185  recv_thread_.interrupt();
186  if (!recv_thread_.timed_join(boost::posix_time::time_duration(0,0,1,0)))
187  {
188  ROS_WARN("Failed second join to recv thread");
189  }
190  }
191  socket_.close();
192 }
193 
194 
196 {
197  // Wait upto 100ms for new data
198  bool got_new_data = false;
199  {
200  boost::mutex::scoped_lock lock(mutex_);
201  unsigned current_packet_count = packet_count_;
202  condition_.timed_wait(lock, boost::posix_time::milliseconds(100));
203  got_new_data = packet_count_ != current_packet_count;
204  }
205 
206  return got_new_data;
207 }
208 
209 
211 {
212  // Command NetFT to start data transmission
213  RDTCommand start_transmission;
215  start_transmission.sample_count_ = RDTCommand::INFINITE_SAMPLES;
216  // TODO change buffer into boost::array
217  uint8_t buffer[RDTCommand::RDT_COMMAND_SIZE];
218  start_transmission.pack(buffer);
219  socket_.send(boost::asio::buffer(buffer, RDTCommand::RDT_COMMAND_SIZE));
220 }
221 
222 
223 
225 {
226  try {
227  recv_thread_running_ = true;
228  RDTRecord rdt_record;
229  geometry_msgs::WrenchStamped tmp_data;
230  uint8_t buffer[RDTRecord::RDT_RECORD_SIZE+1];
231  while (!stop_recv_thread_)
232  {
233  size_t len = socket_.receive(boost::asio::buffer(buffer, RDTRecord::RDT_RECORD_SIZE+1));
234  if (len != RDTRecord::RDT_RECORD_SIZE)
235  {
236  ROS_WARN("Receive size of %d bytes does not match expected size of %d",
237  int(len), int(RDTRecord::RDT_RECORD_SIZE));
238  }
239  else
240  {
241  rdt_record.unpack(buffer);
242  if (rdt_record.status_ != 0)
243  {
244  // Latch any system status error code
245  boost::unique_lock<boost::mutex> lock(mutex_);
246  system_status_ = rdt_record.status_;
247  }
248  int32_t seqdiff = int32_t(rdt_record.rdt_sequence_ - last_rdt_sequence_);
249  last_rdt_sequence_ = rdt_record.rdt_sequence_;
250  if (seqdiff < 1)
251  { boost::unique_lock<boost::mutex> lock(mutex_);
252  // Don't use data that is old
254  }
255  else
256  {
257  tmp_data.header.seq = seq_counter_++;
258  tmp_data.header.stamp = ros::Time::now();
259  tmp_data.header.frame_id = "base_link";
260  tmp_data.wrench.force.x = double(rdt_record.fx_) * force_scale_;
261  tmp_data.wrench.force.y = double(rdt_record.fy_) * force_scale_;
262  tmp_data.wrench.force.z = double(rdt_record.fz_) * force_scale_;
263  tmp_data.wrench.torque.x = double(rdt_record.tx_) * torque_scale_;
264  tmp_data.wrench.torque.y = double(rdt_record.ty_) * torque_scale_;
265  tmp_data.wrench.torque.z = double(rdt_record.tz_) * torque_scale_;
266  { boost::unique_lock<boost::mutex> lock(mutex_);
267  new_data_ = tmp_data;
268  lost_packets_ += (seqdiff - 1);
269  ++packet_count_;
270  condition_.notify_all();
271  }
272  }
273  }
274  } // end while
275  }
276  catch (std::exception &e)
277  {
278  recv_thread_running_ = false;
279  { boost::unique_lock<boost::mutex> lock(mutex_);
280  recv_thread_error_msg_ = e.what();
281  }
282  }
283 }
284 
285 
286 void NetFTRDTDriver::getData(geometry_msgs::WrenchStamped &data)
287 {
288  { boost::unique_lock<boost::mutex> lock(mutex_);
289  data = new_data_;
290  }
291 }
292 
293 
295 {
296  // Publish diagnostics
297  d.name = "NetFT RDT Driver : " + address_;
298 
299  d.summary(d.OK, "OK");
300  d.hardware_id = "0";
301 
303  {
304  d.mergeSummary(d.ERROR, "No new data in last second");
305  }
306 
308  {
309  d.mergeSummaryf(d.ERROR, "Receive thread has stopped : %s", recv_thread_error_msg_.c_str());
310  }
311 
312  if (system_status_ != 0)
313  {
314  d.mergeSummaryf(d.ERROR, "NetFT reports error 0x%08x", system_status_);
315  }
316 
317  ros::Time current_time(ros::Time::now());
318  double recv_rate = double(int32_t(packet_count_ - diag_packet_count_)) / (current_time - last_diag_pub_time_).toSec();
319 
320  d.clear();
321  d.addf("IP Address", "%s", address_.c_str());
322  d.addf("System status", "0x%08x", system_status_);
323  d.addf("Good packets", "%u", packet_count_);
324  d.addf("Lost packets", "%u", lost_packets_);
325  d.addf("Out-of-order packets", "%u", out_of_order_count_);
326  d.addf("Recv rate (pkt/sec)", "%.2f", recv_rate);
327  d.addf("Force scale (N/bit)", "%f", force_scale_);
328  d.addf("Torque scale (Nm/bit)", "%f", torque_scale_);
329 
330  geometry_msgs::WrenchStamped data;
331  getData(data);
332  d.addf("Force X (N)", "%f", data.wrench.force.x);
333  d.addf("Force Y (N)", "%f", data.wrench.force.y);
334  d.addf("Force Z (N)", "%f", data.wrench.force.z);
335  d.addf("Torque X (Nm)", "%f", data.wrench.torque.x);
336  d.addf("Torque Y (Nm)", "%f", data.wrench.torque.y);
337  d.addf("Torque Z (Nm)", "%f", data.wrench.torque.z);
338 
339  last_diag_pub_time_ = current_time;
341 }
342 
343 
344 } // end namespace netft_rdt_driver
345 
unsigned out_of_order_count_
Counts number of out-of-order (or duplicate) received packets.
void getData(geometry_msgs::WrenchStamped &data)
Get newest RDT data from netFT device.
uint32_t system_status_
to keep track of any error codes reported by netft
double force_scale_
Scaling factor for converting raw force values from device into Newtons.
void summary(unsigned char lvl, const std::string s)
void unpack(const uint8_t *buffer)
bool recv_thread_running_
True if recv loop is still running.
void startStreaming(void)
Asks NetFT to start streaming data.
data
unsigned packet_count_
Count number of received <good> packets.
#define ROS_WARN(...)
void pack(uint8_t *buffer) const
Packet structure into buffer for network transport.
void addf(const std::string &key, const char *format,...)
geometry_msgs::WrenchStamped new_data_
Newest data received from netft device.
bool waitForNewData(void)
Wait for new NetFT data to arrive.
std::string recv_thread_error_msg_
Set if recv thread exited because of error.
unsigned lost_packets_
Count of lost RDT packets using RDT sequence number.
ros::Time last_diag_pub_time_
Last time diagnostics was published.
boost::asio::ip::udp::socket socket_
void mergeSummary(unsigned char lvl, const std::string s)
static uint32_t unpack32(const uint8_t *buffer)
uint32_t last_rdt_sequence_
to keep track of out-of-order or duplicate packet
unsigned diag_packet_count_
Packet count last time diagnostics thread published output.
static Time now()
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Add device diagnostics status wrapper.
void mergeSummaryf(unsigned char lvl, const char *format,...)
NetFTRDTDriver(const std::string &address)
unsigned seq_counter_
Incremental counter for wrench header.
double torque_scale_
Scaling factor for converting raw torque values into Newton*meters.


netft_utils
Author(s): Alex von Sternberg , Derek King, Andy Zelenak
autogenerated on Tue Mar 2 2021 03:15:08