netft_utils_lean.cpp
Go to the documentation of this file.
1 
2 /*
3 Copyright (c) 2016, Los Alamos National Security, LLC
4 All rights reserved.
5 Copyright 2016. Los Alamos National Security, LLC. This software was produced under U.S. Government contract DE-AC52-06NA25396 for Los Alamos National Laboratory (LANL), which is operated by Los Alamos National Security, LLC for the U.S. Department of Energy. The U.S. Government has rights to use, reproduce, and distribute this software. NEITHER THE GOVERNMENT NOR LOS ALAMOS NATIONAL SECURITY, LLC MAKES ANY WARRANTY, EXPRESS OR IMPLIED, OR ASSUMES ANY LIABILITY FOR THE USE OF THIS SOFTWARE. If software is modified to produce derivative works, such modified software should be clearly marked, so as not to confuse it with the version available from LANL.
6 
7 Additionally, redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
8 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
9 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
10 3. Neither the name of Los Alamos National Security, LLC, Los Alamos National Laboratory, LANL, the U.S. Government, nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
11 
12 THIS SOFTWARE IS PROVIDED BY LOS ALAMOS NATIONAL SECURITY, LLC AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL LOS ALAMOS NATIONAL SECURITY, LLC OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
13 
14 Author: Alex von Sternberg
15 */
16 
17 #include "netft_utils_lean.h"
18 
20  n(nh),
21  ftAddress(""),
22  ftTopic(""),
23  isInit(false),
24  hasData(false),
25  cycleRate(0.0),
26  isFilterOn(false),
27  deltaTFilter(0.0),
28  cutoffFrequency(0.0),
29  newFilter(false),
30  lpExists(false),
31  isBiased(false),
32  isNewBias(false),
33  waitingForTransform(true),
34  isActive(false),
35  cancel_count(MAX_CANCEL),
36  cancel_wait(MAX_WAIT),
37  forceMaxB(10.0),
38  torqueMaxB(0.8),
39  forceMaxU(50.0),
40  torqueMaxU(5.0),
41  toUpdate(false),
42  toMonitor(false)
43 {
44 }
45 
47 {
48  delete listener;
49  if(lpExists)
50  delete lp;
51 }
52 
53 bool NetftUtilsLean::initialize(double rate, std::string world, std::string ft, double force, double torque)
54 {
55  // Set the user input
56  if(!setUserInput(world, ft, force, torque))
57  {
58  return false;
59  }
60  // Set the cycle rate
61  if(rate>0.001)
62  {
63  cycleRate = rate;
64  }
65  else
66  {
67  ROS_ERROR_STREAM("Cycle rate should be positive");
68  return false;
69  }
70 
71  // Set up access to netft data
72  if(!ftTopic.empty())
73  {
74  ft_sub = n->subscribe<geometry_msgs::WrenchStamped>(ftTopic, 1, &NetftUtilsLean::dataCallback, this);
75  ROS_INFO_STREAM("Using NETFT topic instead of IP because ftTopic is:" << ftTopic);
76  }
77  else if(!ftAddress.empty())
78  {
79  try
80  {
81  netft = std::unique_ptr<netft_rdt_driver::NetFTRDTDriver>(new netft_rdt_driver::NetFTRDTDriver(ftAddress));
82  }
83  catch(std::runtime_error)
84  {
85  ROS_ERROR_STREAM("Could not access data from netft_rdt_driver");
86  return false;
87  }
88  }
89  else
90  {
91  ROS_ERROR_STREAM("Can not initialize FT, must set topic or address first.");
92  return false;
93  }
94 
95  //Zero out the zero wrench
96  zero_wrench.wrench.force.x = 0.0;
97  zero_wrench.wrench.force.y = 0.0;
98  zero_wrench.wrench.force.z = 0.0;
99  zero_wrench.wrench.torque.x = 0.0;
100  zero_wrench.wrench.torque.y = 0.0;
101  zero_wrench.wrench.torque.z = 0.0;
102 
103  //Initialize cancel message
104  cancel_msg.toCancel = false;
105 
106  //Listen to the transfomation from the ft sensor to world frame.
108 
109  //Publish on the /cancel topic. Queue up to 100000 data points
110  netft_cancel_pub = n->advertise<netft_utils::Cancel>("/netft/cancel", 100000);
111 
112  if(DEBUG_DATA)
113  data_pub = n->advertise<geometry_msgs::WrenchStamped>("/netft/netft_data", 100000);
114 
115  isInit = true;
116  return true;
117 }
118 
120 {
121  if(!isInit)
122  {
123  ROS_ERROR_STREAM("Cannot run before initialization is successful.");
124  return false;
125  }
126 
127  isActive = true;
128 
129  toUpdate = true;
130  toMonitor = true;
131 
132  //Spin off update thread
133  updateThread = std::async(std::launch::async, &NetftUtilsLean::update, this);
134 
135  //Spin off thread to monitor netft data
136  if(!ftAddress.empty())
137  {
138  monitorThread = std::async(std::launch::async, &NetftUtilsLean::monitorData, this);
139  }
140 
141  //Join threads
142  if(!ftAddress.empty())
143  {
144  monitorThread.get();
145  }
146  updateThread.get();
147 
148  isActive = false;
149  return true;
150 }
151 
153 {
154  toUpdate = false;
155  toMonitor = false;
156 }
157 
159 {
160  while(waitingForTransform)
161  {
162  ros::Duration(0.05).sleep();
163  }
164  ros::Rate r(cycleRate);
165  while (ros::ok() && toMonitor)
166  {
167  //ros::Time tempTime = ros::Time::now();
168  if (netft->waitForNewData())
169  {
170  //std::cout << "Time waiting for new data: " <<ros::Time::now().toSec()-tempTime.toSec() << std::endl;
171  geometry_msgs::WrenchStamped data;
172  //tempTime = ros::Time::now();
173  netft->getData(data);
174  //std::cout << "Time to get data: " <<ros::Time::now().toSec()-tempTime.toSec() << std::endl;
175  //tempTime = ros::Time::now();
176  netftCallback(data);
177  //std::cout << "Time in netftCallback: " <<ros::Time::now().toSec()-tempTime.toSec() << std::endl;
178  hasData = true;
179  }
180  //std::cout << "Monitoring!!!!!!" << std::endl;
181  //tempTime = ros::Time::now();
182  r.sleep();
183  //std::cout << "Time sleeping: " <<ros::Time::now().toSec()-tempTime.toSec() << std::endl;
184  }
185  hasData = false;
186  return true;
187 }
188 
189 void NetftUtilsLean::dataCallback(const geometry_msgs::WrenchStamped::ConstPtr& msg)
190 {
192  {
194  raw_topic_data.header = msg->header;
195  raw_topic_data.wrench = msg->wrench;
197  hasData = true;
198  }
199  else
200  hasData = false;
201 }
202 
204 {
205  return hasData;
206 }
207 
208 bool NetftUtilsLean::waitForData(double timeout)
209 {
210  ros::Time startWait = ros::Time::now();
211  while((ros::Time::now().toSec() - startWait.toSec()) < timeout && !hasData)
212  {
213  ros::Duration(0.001).sleep();
214  }
215  return hasData;
216 }
217 
218 bool NetftUtilsLean::setUserInput(std::string world, std::string ft, double force, double torque)
219 {
220  if(world.compare("") == 0)
221  {
222  ROS_ERROR_STREAM("World frame string cannot be empty");
223  return false;
224  }
225  world_frame = world;
226  ROS_INFO_STREAM("World frame: " << world_frame);
227  if(ft.compare("") == 0)
228  {
229  ROS_ERROR_STREAM("FT frame string cannot be empty");
230  return false;
231  }
232  ft_frame = ft;
233  ROS_INFO_STREAM("FT frame: " << ft_frame);
234  if(force >= 0.001)
235  {
236  forceMaxU = force;
237  }
238  else
239  {
240  ROS_ERROR_STREAM("FT max force must be positive");
241  return false;
242  }
243  if(torque >= 0.001)
244  {
245  torqueMaxU = torque;
246  }
247  else
248  {
249  ROS_ERROR_STREAM("FT max torque must be positive");
250  return false;
251  }
252  return true;
253 }
254 
256 {
257  if(!isInit)
258  {
259  ROS_ERROR_STREAM("Cannot update until NetftUtilsLean is initialized properly.");
260  return false;
261  }
262  ros::Rate r(cycleRate);
263  while (ros::ok() && toUpdate)
264  {
265  // Check for a filter
266  if(newFilter)
267  {
268  if(lpExists)
269  delete lp;
271  lpExists = true;
272  newFilter = false;
273  }
274 
275  // Look up transform from ft to world frame
276  tf::StampedTransform tempTransform;
277  try
278  {
280  listener->lookupTransform(world_frame, ft_frame, ros::Time(0), tempTransform);
281  }
282  catch (tf::TransformException ex)
283  {
284  ROS_ERROR("%s",ex.what());
285  }
286 
287  // Set translation to zero before updating value
288  tempTransform.setOrigin(tf::Vector3(0.0,0.0,0.0));
289  ft_to_world = tempTransform;
290  waitingForTransform = false;
291 
292  checkMaxForce();
293 
294  // Publish cancel_msg
296  r.sleep();
297  }
298  return true;
299 }
300 
301 void NetftUtilsLean::copyWrench(geometry_msgs::WrenchStamped &in, geometry_msgs::WrenchStamped &out, geometry_msgs::WrenchStamped &diff)
302 {
303  out.header.stamp = in.header.stamp;
304  out.header.frame_id = in.header.frame_id;
305  out.wrench.force.x = in.wrench.force.x - diff.wrench.force.x;
306  out.wrench.force.y = in.wrench.force.y - diff.wrench.force.y;
307  out.wrench.force.z = in.wrench.force.z - diff.wrench.force.z;
308  out.wrench.torque.x = in.wrench.torque.x - diff.wrench.torque.x;
309  out.wrench.torque.y = in.wrench.torque.y - diff.wrench.torque.y;
310  out.wrench.torque.z = in.wrench.torque.z - diff.wrench.torque.z;
311 }
312 
313 void NetftUtilsLean::applyThreshold(double &value, double thresh)
314 {
315  if(value <= thresh && value >= -thresh)
316  {
317  value = 0.0;
318  }
319 }
320 
321 void NetftUtilsLean::transformFrame(geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data, char target_frame)
322 {
323  tf::Vector3 tempF;
324  tf::Vector3 tempT;
325  tempF.setX(in_data.wrench.force.x);
326  tempF.setY(in_data.wrench.force.y);
327  tempF.setZ(in_data.wrench.force.z);
328  tempT.setX(in_data.wrench.torque.x);
329  tempT.setY(in_data.wrench.torque.y);
330  tempT.setZ(in_data.wrench.torque.z);
331  if(target_frame == 'w')
332  {
333  out_data.header.frame_id = world_frame;
334  tempF = ft_to_world * tempF;
335  tempT = ft_to_world * tempT;
336  }
337  else if(target_frame == 't')
338  {
339  out_data.header.frame_id = ft_frame;
340  tempF = ft_to_world.inverse() * tempF;
341  tempT = ft_to_world.inverse() * tempT;
342  }
343  out_data.header.stamp = in_data.header.stamp;
344  out_data.wrench.force.x = tempF.getX();
345  out_data.wrench.force.y = tempF.getY();
346  out_data.wrench.force.z = tempF.getZ();
347  out_data.wrench.torque.x = tempT.getX();
348  out_data.wrench.torque.y = tempT.getY();
349  out_data.wrench.torque.z = tempT.getZ();
350 }
351 
352 void NetftUtilsLean::netftCallback(const geometry_msgs::WrenchStamped& data)
353 {
354  // Filter data. apply negative to x data to follow right hand rule convention (ft raw data does not)
355  std::vector<double> tempData;
356  tempData.resize(6);
357  if(!ftAddress.empty())
358  {
359  tempData.at(0) = -data.wrench.force.x;
360  tempData.at(1) = data.wrench.force.y;
361  tempData.at(2) = data.wrench.force.z;
362  tempData.at(3) = -data.wrench.torque.x;
363  tempData.at(4) = data.wrench.torque.y;
364  tempData.at(5) = data.wrench.torque.z;
365  }
366  else
367  {
368  tempData.at(0) = data.wrench.force.x;
369  tempData.at(1) = data.wrench.force.y;
370  tempData.at(2) = data.wrench.force.z;
371  tempData.at(3) = data.wrench.torque.x;
372  tempData.at(4) = data.wrench.torque.y;
373  tempData.at(5) = data.wrench.torque.z;
374  }
375 
376  if(isFilterOn && !newFilter)
377  lp->update(tempData,tempData);
378 
379  // Copy tool frame data.
380  raw_data_tool.header.stamp = data.header.stamp;
381  raw_data_tool.header.frame_id = ft_frame;
382  raw_data_tool.wrench.force.x = tempData.at(0);
383  raw_data_tool.wrench.force.y = tempData.at(1);
384  raw_data_tool.wrench.force.z = tempData.at(2);
385  raw_data_tool.wrench.torque.x = tempData.at(3);
386  raw_data_tool.wrench.torque.y = tempData.at(4);
387  raw_data_tool.wrench.torque.z = tempData.at(5);
388 
389  // Apply bias
391 
392  // Copy in new netft data in tool frame and transform to world frame
394 
395  // Apply thresholds
396  applyThreshold(tf_data_world.wrench.force.x, threshold.wrench.force.x);
397  applyThreshold(tf_data_world.wrench.force.y, threshold.wrench.force.y);
398  applyThreshold(tf_data_world.wrench.force.z, threshold.wrench.force.z);
399  applyThreshold(tf_data_world.wrench.torque.x, threshold.wrench.torque.x);
400  applyThreshold(tf_data_world.wrench.torque.y, threshold.wrench.torque.y);
401  applyThreshold(tf_data_world.wrench.torque.z, threshold.wrench.torque.z);
402  applyThreshold(tf_data_tool.wrench.force.x, threshold.wrench.force.x);
403  applyThreshold(tf_data_tool.wrench.force.y, threshold.wrench.force.y);
404  applyThreshold(tf_data_tool.wrench.force.z, threshold.wrench.force.z);
405  applyThreshold(tf_data_tool.wrench.torque.x, threshold.wrench.torque.x);
406  applyThreshold(tf_data_tool.wrench.torque.y, threshold.wrench.torque.y);
407  applyThreshold(tf_data_tool.wrench.torque.z, threshold.wrench.torque.z);
408 
409  // Publish data for debugging
410  if(DEBUG_DATA)
412  //ROS_INFO_STREAM("Callback time: " << tf_data_tool.header.stamp.toSec()-ros::Time::now().toSec());
413 }
414 
415 bool NetftUtilsLean::biasSensor(bool toBias)
416 {
417  if(toBias)
418  {
419  if(!hasData)
420  {
421  geometry_msgs::WrenchStamped data;
422  if(!ftTopic.empty())
423  {
424  ros::Time startTime = ros::Time::now();
425  while(ros::Time::now().toSec()-startTime.toSec() < 0.1 && !hasData)
426  {
427  ros::Duration(0.01).sleep();
428  }
429  if(hasData)
430  {
431  data = raw_topic_data;
432  }
433  else
434  {
435  ROS_ERROR("Bias sensor failed.");
436  return false;
437  }
438  }
439  else
440  {
441  if (netft->waitForNewData())
442  {
443  netft->getData(data);
444  }
445  else
446  {
447  ROS_ERROR("Bias sensor failed.");
448  return false;
449  }
450  }
451  // Copy tool frame data.
452  raw_data_tool.header.stamp = data.header.stamp;
453  raw_data_tool.header.frame_id = ft_frame;
454  raw_data_tool.wrench.force.x = -data.wrench.force.x;
455  raw_data_tool.wrench.force.y = data.wrench.force.y;
456  raw_data_tool.wrench.force.z = data.wrench.force.z;
457  raw_data_tool.wrench.torque.x = -data.wrench.torque.x;
458  raw_data_tool.wrench.torque.y = data.wrench.torque.y;
459  raw_data_tool.wrench.torque.z = data.wrench.torque.z;
460  }
462  isNewBias = true;
463  }
464  else
465  {
467  }
468  isBiased = toBias;
469  return true;
470 }
471 
472 bool NetftUtilsLean::setFilter(bool toFilter, double deltaT, double cutoffFreq)
473 {
474  if(toFilter)
475  {
476  newFilter = true;
477  isFilterOn = true;
478  deltaTFilter = deltaT;
479  cutoffFrequency = cutoffFreq;
480  }
481  else
482  {
483  isFilterOn = false;
484  }
485 
486  return true;
487 }
488 
489 bool NetftUtilsLean::setMax(double fMaxU, double tMaxU, double fMaxB, double tMaxB)
490 {
491  if(fMaxU >= 0.0001)
492  {
493  forceMaxU = fMaxU;
494  torqueMaxU = tMaxU;
495  forceMaxB = fMaxB;
496  torqueMaxB = tMaxB;
497  return true;
498  }
499  else
500  {
501  ROS_ERROR_STREAM("All maximum FT values must be positive.");
502  return false;
503  }
504 }
505 
506 bool NetftUtilsLean::setThreshold(double fThresh, double tThresh)
507 {
508  threshold.wrench.force.x = fThresh;
509  threshold.wrench.force.y = fThresh;
510  threshold.wrench.force.z = fThresh;
511  threshold.wrench.torque.x = tThresh;
512  threshold.wrench.torque.y = tThresh;
513  threshold.wrench.torque.z = tThresh;
514 
515  return true;
516 }
517 
519 {
520  double fMag = pow((pow(tf_data_tool.wrench.force.x, 2.0) + pow(tf_data_tool.wrench.force.y, 2.0) + pow(tf_data_tool.wrench.force.z, 2.0)), 0.5);
521  double tMag = pow((pow(tf_data_tool.wrench.torque.x, 2.0) + pow(tf_data_tool.wrench.torque.y, 2.0) + pow(tf_data_tool.wrench.torque.z, 2.0)), 0.5);
522  double fMax;
523  double tMax;
524  if(isBiased && !isNewBias)
525  {
526  if(forceMaxB > 0.001 && torqueMaxB > 0.001)
527  {
528  fMax = forceMaxB;
529  tMax = torqueMaxB;
530  }
531  else
532  {
533  fMax = forceMaxU;
534  tMax = torqueMaxU;
535  }
536  }
537  else
538  {
539  if(isBiased && isNewBias)
540  {
541  isNewBias = false;
542  }
543  fMax = forceMaxU;
544  tMax = torqueMaxU;
545  }
546 
547  // If max FT exceeded, send cancel unless we have just sent it MAX_CANCEL times
548  //ROS_INFO("FMAG: %f TMAG: %f", fMag, tMag);
549  if((fabs(fMag) > fMax || fabs(tMag) > tMax) && cancel_count > 0)
550  {
551  cancel_msg.toCancel = true;
552  //ROS_INFO("Force torque violation. Canceling move.");
553  ROS_INFO("FMAG: %f FMAX: %f TMAG:%f TMAX: %f count: %d wait: %d", fMag, fMax, tMag, tMax, cancel_count, cancel_wait);
554  cancel_count-=1;
555  }
556  // If we have sent cancel MAX_CANCEL times, don't send cancel again for MAX_WAIT cycles
557  else if(cancel_count == 0 && cancel_wait > 0 && cancel_wait <= MAX_WAIT)
558  {
559  cancel_msg.toCancel = false;
560  cancel_wait-=1;
561  }
562  // If we have just finished waiting MAX_WAIT times, or the max force is no longer exceeded, reset cancel_count and cancel_wait
563  else if(cancel_wait == 0 || !(fabs(fMag) > fMax || fabs(tMag) > tMax))
564  {
565  cancel_msg.toCancel = false;
568  }
569 }
570 
571 void NetftUtilsLean::setFTAddress(std::string ftAd)
572 {
573  ftAddress = ftAd;
574 }
575 
576 void NetftUtilsLean::setFTTopic(std::string ftTop)
577 {
578  ftTopic = ftTop;
579 }
580 
581 void NetftUtilsLean::getRawData(geometry_msgs::WrenchStamped& data)
582 {
583  data = raw_data_tool;
584 }
585 
586 void NetftUtilsLean::getToolData(geometry_msgs::WrenchStamped& data)
587 {
588  data = tf_data_tool;
589 }
590 
591 void NetftUtilsLean::getWorldData(geometry_msgs::WrenchStamped& data)
592 {
593  data = tf_data_world;
594 }
595 
597 {
598  return isActive;
599 }
600 
tf::StampedTransform ft_to_world
void transformFrame(geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data, char target_frame)
std::string ft_frame
bool biasSensor(bool toBias)
void publish(const boost::shared_ptr< M > &message) const
TFSIMD_FORCE_INLINE void setX(tfScalar x)
bool update(std::vector< double > input, std::vector< double > &output)
Definition: lpfilter.cpp:66
TFSIMD_FORCE_INLINE void setY(tfScalar y)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Publisher netft_cancel_pub
void setFTTopic(std::string ftTopic)
bool sleep() const
std::unique_ptr< netft_rdt_driver::NetFTRDTDriver > netft
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
std::string ftAddress
std::future< bool > monitorThread
data
geometry_msgs::WrenchStamped raw_topic_data
TFSIMD_FORCE_INLINE const tfScalar & getY() const
geometry_msgs::WrenchStamped raw_data_tool
bool setMax(double fMaxU, double tMaxU, double fMaxB, double tMaxB)
geometry_msgs::WrenchStamped threshold
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
void applyThreshold(double &value, double thresh)
tf::TransformListener * listener
ros::Publisher data_pub
std::string ftTopic
void setFTAddress(std::string ftAddress)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
geometry_msgs::WrenchStamped tf_data_world
TFSIMD_FORCE_INLINE const tfScalar & x() const
void copyWrench(geometry_msgs::WrenchStamped &in, geometry_msgs::WrenchStamped &out, geometry_msgs::WrenchStamped &bias)
void dataCallback(const geometry_msgs::WrenchStamped::ConstPtr &msg)
void getWorldData(geometry_msgs::WrenchStamped &data)
#define ROS_INFO(...)
static const bool DEBUG_DATA
static const int MAX_CANCEL
ROSCPP_DECL bool ok()
bool setFilter(bool toFilter, double deltaT, double cutoffFreq)
geometry_msgs::WrenchStamped tf_data_tool
std::future< bool > updateThread
Transform inverse() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
bool sleep()
bool setUserInput(std::string world, std::string ft, double force, double torque)
netft_utils::Cancel cancel_msg
NetftUtilsLean(ros::NodeHandle *nh)
#define ROS_INFO_STREAM(args)
ros::Subscriber ft_sub
geometry_msgs::WrenchStamped bias
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static Time now()
geometry_msgs::WrenchStamped zero_wrench
void getRawData(geometry_msgs::WrenchStamped &data)
#define ROS_ERROR_STREAM(args)
void getToolData(geometry_msgs::WrenchStamped &data)
bool initialize(double rate, std::string world, std::string ft, double force=60.0, double torque=6.0)
ros::NodeHandle * n
#define ROS_ERROR(...)
std::string world_frame
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
bool setThreshold(double fThresh, double tThresh)
bool waitForData(double timeout)
static const int MAX_WAIT
void netftCallback(const geometry_msgs::WrenchStamped &data)


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