netft_utils_lean.cpp
Go to the documentation of this file.
00001 
00002 /*
00003 Copyright (c) 2016, Los Alamos National Security, LLC
00004 All rights reserved.
00005 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.
00006 
00007 Additionally, redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
00008 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
00009 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.
00010 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.
00011 
00012 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.
00013 
00014 Author: Alex von Sternberg
00015 */
00016 
00017 #include "netft_utils_lean.h"
00018 
00019 NetftUtilsLean::NetftUtilsLean(ros::NodeHandle* nh) :
00020   n(nh),
00021   ftAddress(""),
00022   ftTopic(""),
00023   isInit(false),
00024   hasData(false),
00025   cycleRate(0.0),
00026   isFilterOn(false),
00027   deltaTFilter(0.0),
00028   cutoffFrequency(0.0),
00029   newFilter(false),
00030   lpExists(false),
00031   isBiased(false),
00032   isNewBias(false),
00033   waitingForTransform(true),
00034   isActive(false),
00035   cancel_count(MAX_CANCEL),
00036   cancel_wait(MAX_WAIT),
00037   forceMaxB(10.0),
00038   torqueMaxB(0.8),
00039   forceMaxU(50.0),
00040   torqueMaxU(5.0),
00041   toUpdate(false),
00042   toMonitor(false)
00043 {
00044 }
00045 
00046 NetftUtilsLean::~NetftUtilsLean()
00047 {
00048   delete listener;
00049   if(lpExists)
00050     delete lp;
00051 }
00052 
00053 bool NetftUtilsLean::initialize(double rate, std::string world, std::string ft, double force, double torque)
00054 {
00055   // Set the user input
00056   if(!setUserInput(world, ft, force, torque))
00057   {
00058     return false;
00059   }
00060   // Set the cycle rate
00061   if(rate>0.001)
00062   {
00063     cycleRate = rate;
00064   }
00065   else
00066   {
00067     ROS_ERROR_STREAM("Cycle rate should be positive");
00068     return false;
00069   }
00070 
00071   // Set up access to netft data
00072   if(!ftTopic.empty())
00073   {
00074     ft_sub = n->subscribe<geometry_msgs::WrenchStamped>(ftTopic, 1, &NetftUtilsLean::dataCallback, this);
00075     ROS_INFO_STREAM("Using NETFT topic instead of IP because ftTopic is:" << ftTopic);
00076   }
00077   else if(!ftAddress.empty())
00078   {
00079     try
00080     {
00081       netft = std::unique_ptr<netft_rdt_driver::NetFTRDTDriver>(new netft_rdt_driver::NetFTRDTDriver(ftAddress));
00082     }
00083     catch(std::runtime_error)
00084     {
00085       ROS_ERROR_STREAM("Could not access data from netft_rdt_driver");
00086       return false;
00087     }
00088   }
00089   else
00090   {
00091       ROS_ERROR_STREAM("Can not initialize FT, must set topic or address first.");
00092       return false;
00093   }
00094 
00095   //Zero out the zero wrench
00096   zero_wrench.wrench.force.x = 0.0;
00097   zero_wrench.wrench.force.y = 0.0;
00098   zero_wrench.wrench.force.z = 0.0;
00099   zero_wrench.wrench.torque.x = 0.0;
00100   zero_wrench.wrench.torque.y = 0.0;
00101   zero_wrench.wrench.torque.z = 0.0;
00102 
00103   //Initialize cancel message
00104   cancel_msg.toCancel = false;
00105 
00106   //Listen to the transfomation from the ft sensor to world frame.
00107   listener = new tf::TransformListener(ros::Duration(300));
00108 
00109   //Publish on the /cancel topic. Queue up to 100000 data points
00110   netft_cancel_pub = n->advertise<netft_utils::Cancel>("/netft/cancel", 100000);
00111 
00112   if(DEBUG_DATA)
00113     data_pub = n->advertise<geometry_msgs::WrenchStamped>("/netft/netft_data", 100000);
00114 
00115   isInit = true;
00116   return true;
00117 }
00118 
00119 bool NetftUtilsLean::run()
00120 {
00121   if(!isInit)
00122   {
00123     ROS_ERROR_STREAM("Cannot run before initialization is successful.");
00124     return false;
00125   }
00126 
00127   isActive = true;
00128 
00129   toUpdate = true;
00130   toMonitor = true;
00131 
00132   //Spin off update thread
00133   updateThread = std::async(std::launch::async, &NetftUtilsLean::update, this);
00134 
00135   //Spin off thread to monitor netft data
00136   if(!ftAddress.empty())
00137   {
00138     monitorThread = std::async(std::launch::async, &NetftUtilsLean::monitorData, this);
00139   }
00140 
00141   //Join threads
00142   if(!ftAddress.empty())
00143   {
00144     monitorThread.get();
00145   }
00146   updateThread.get();
00147 
00148   isActive = false;
00149   return true;
00150 }
00151 
00152 void NetftUtilsLean::stop()
00153 {
00154   toUpdate = false;
00155   toMonitor = false;
00156 }
00157 
00158 bool NetftUtilsLean::monitorData()
00159 {
00160   while(waitingForTransform)
00161   {
00162     ros::Duration(0.05).sleep();
00163   }
00164   ros::Rate r(cycleRate);
00165   while (ros::ok() && toMonitor)
00166   {
00167     //ros::Time tempTime = ros::Time::now();
00168     if (netft->waitForNewData())
00169     {
00170       //std::cout << "Time waiting for new data: " <<ros::Time::now().toSec()-tempTime.toSec() << std::endl;
00171       geometry_msgs::WrenchStamped data;
00172       //tempTime = ros::Time::now();
00173       netft->getData(data);
00174       //std::cout << "Time to get data: " <<ros::Time::now().toSec()-tempTime.toSec() << std::endl;
00175       //tempTime = ros::Time::now();
00176       netftCallback(data);
00177       //std::cout << "Time in netftCallback: " <<ros::Time::now().toSec()-tempTime.toSec() << std::endl;
00178       hasData = true;
00179     }
00180     //std::cout << "Monitoring!!!!!!" << std::endl;
00181     //tempTime = ros::Time::now();
00182     r.sleep();
00183     //std::cout << "Time sleeping: " <<ros::Time::now().toSec()-tempTime.toSec() << std::endl;
00184   }
00185   hasData = false;
00186   return true;
00187 }
00188 
00189 void NetftUtilsLean::dataCallback(const geometry_msgs::WrenchStamped::ConstPtr& msg)
00190 {
00191   if(!waitingForTransform && toMonitor)
00192   {
00193     raw_topic_data;
00194     raw_topic_data.header = msg->header;
00195     raw_topic_data.wrench = msg->wrench;
00196     netftCallback(raw_topic_data);
00197     hasData = true;
00198   }
00199   else
00200     hasData = false;
00201 }
00202 
00203 bool NetftUtilsLean::isReady()
00204 {
00205   return hasData;
00206 }
00207 
00208 bool NetftUtilsLean::waitForData(double timeout)
00209 {
00210   ros::Time startWait = ros::Time::now();
00211   while((ros::Time::now().toSec() - startWait.toSec()) < timeout && !hasData)
00212   {
00213     ros::Duration(0.001).sleep();
00214   }
00215   return hasData;
00216 }
00217 
00218 bool NetftUtilsLean::setUserInput(std::string world, std::string ft, double force, double torque)
00219 {
00220   if(world.compare("") == 0)
00221   {
00222     ROS_ERROR_STREAM("World frame string cannot be empty");
00223     return false;
00224   }
00225   world_frame = world;
00226   ROS_INFO_STREAM("World frame: " << world_frame);
00227   if(ft.compare("") == 0)
00228   {
00229     ROS_ERROR_STREAM("FT frame string cannot be empty");
00230     return false;
00231   }
00232   ft_frame = ft;
00233   ROS_INFO_STREAM("FT frame: " << ft_frame);
00234   if(force >= 0.001)
00235   {
00236     forceMaxU = force;
00237   }
00238   else
00239   {
00240     ROS_ERROR_STREAM("FT max force must be positive");
00241     return false;
00242   }
00243   if(torque >= 0.001)
00244   {
00245     torqueMaxU = torque;
00246   }
00247   else
00248   {
00249     ROS_ERROR_STREAM("FT max torque must be positive");
00250     return false;
00251   }
00252   return true;
00253 }
00254 
00255 bool NetftUtilsLean::update()
00256 {
00257   if(!isInit)
00258   {
00259     ROS_ERROR_STREAM("Cannot update until NetftUtilsLean is initialized properly.");
00260     return false;
00261   }
00262   ros::Rate r(cycleRate);
00263   while (ros::ok() && toUpdate)
00264   {
00265     // Check for a filter
00266     if(newFilter)
00267     {
00268       if(lpExists)
00269         delete lp;
00270       lp = new LPFilter(deltaTFilter,cutoffFrequency,6);
00271       lpExists = true;
00272       newFilter = false;
00273     }
00274 
00275     // Look up transform from ft to world frame
00276     tf::StampedTransform tempTransform;
00277     try
00278     {
00279       listener->waitForTransform(world_frame, ft_frame, ros::Time(0), ros::Duration(1.0));
00280       listener->lookupTransform(world_frame, ft_frame, ros::Time(0), tempTransform);
00281     }
00282     catch (tf::TransformException ex)
00283     {
00284       ROS_ERROR("%s",ex.what());
00285     }
00286 
00287     // Set translation to zero before updating value
00288     tempTransform.setOrigin(tf::Vector3(0.0,0.0,0.0));
00289     ft_to_world = tempTransform;
00290     waitingForTransform = false;
00291 
00292     checkMaxForce();
00293 
00294     // Publish cancel_msg
00295     netft_cancel_pub.publish( cancel_msg );
00296     r.sleep();
00297   }
00298   return true;
00299 }
00300 
00301 void NetftUtilsLean::copyWrench(geometry_msgs::WrenchStamped &in, geometry_msgs::WrenchStamped &out, geometry_msgs::WrenchStamped &diff)
00302 {
00303   out.header.stamp = in.header.stamp;
00304   out.header.frame_id = in.header.frame_id;
00305   out.wrench.force.x = in.wrench.force.x - diff.wrench.force.x;
00306   out.wrench.force.y = in.wrench.force.y - diff.wrench.force.y;
00307   out.wrench.force.z = in.wrench.force.z - diff.wrench.force.z;
00308   out.wrench.torque.x = in.wrench.torque.x - diff.wrench.torque.x;
00309   out.wrench.torque.y = in.wrench.torque.y - diff.wrench.torque.y;
00310   out.wrench.torque.z = in.wrench.torque.z - diff.wrench.torque.z;
00311 }
00312 
00313 void NetftUtilsLean::applyThreshold(double &value, double thresh)
00314 {
00315   if(value <= thresh && value >= -thresh)
00316   {
00317     value = 0.0;
00318   }
00319 }
00320 
00321 void NetftUtilsLean::transformFrame(geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data, char target_frame)
00322 {
00323   tf::Vector3 tempF;
00324   tf::Vector3 tempT;
00325   tempF.setX(in_data.wrench.force.x);
00326   tempF.setY(in_data.wrench.force.y);
00327   tempF.setZ(in_data.wrench.force.z);
00328   tempT.setX(in_data.wrench.torque.x);
00329   tempT.setY(in_data.wrench.torque.y);
00330   tempT.setZ(in_data.wrench.torque.z);
00331   if(target_frame == 'w')
00332   {
00333       out_data.header.frame_id = world_frame;
00334       tempF = ft_to_world * tempF;
00335       tempT = ft_to_world * tempT;
00336   }
00337   else if(target_frame == 't')
00338   {
00339       out_data.header.frame_id = ft_frame;
00340       tempF = ft_to_world.inverse() * tempF;
00341       tempT = ft_to_world.inverse() * tempT;
00342   }
00343   out_data.header.stamp = in_data.header.stamp;
00344   out_data.wrench.force.x = tempF.getX();
00345   out_data.wrench.force.y = tempF.getY();
00346   out_data.wrench.force.z = tempF.getZ();
00347   out_data.wrench.torque.x = tempT.getX();
00348   out_data.wrench.torque.y = tempT.getY();
00349   out_data.wrench.torque.z = tempT.getZ();
00350 }
00351 
00352 void NetftUtilsLean::netftCallback(const geometry_msgs::WrenchStamped& data)
00353 {
00354   // Filter data. apply negative to x data to follow right hand rule convention (ft raw data does not)
00355   std::vector<double> tempData;
00356   tempData.resize(6);
00357   if(!ftAddress.empty())
00358   {
00359     tempData.at(0) = -data.wrench.force.x;
00360     tempData.at(1) = data.wrench.force.y;
00361     tempData.at(2) = data.wrench.force.z;
00362     tempData.at(3) = -data.wrench.torque.x;
00363     tempData.at(4) = data.wrench.torque.y;
00364     tempData.at(5) = data.wrench.torque.z;
00365   }
00366   else
00367   {
00368     tempData.at(0) = data.wrench.force.x;
00369     tempData.at(1) = data.wrench.force.y;
00370     tempData.at(2) = data.wrench.force.z;
00371     tempData.at(3) = data.wrench.torque.x;
00372     tempData.at(4) = data.wrench.torque.y;
00373     tempData.at(5) = data.wrench.torque.z;
00374   }
00375 
00376   if(isFilterOn && !newFilter)
00377     lp->update(tempData,tempData);
00378 
00379   // Copy tool frame data.
00380   raw_data_tool.header.stamp = data.header.stamp;
00381   raw_data_tool.header.frame_id = ft_frame;
00382   raw_data_tool.wrench.force.x = tempData.at(0);
00383   raw_data_tool.wrench.force.y = tempData.at(1);
00384   raw_data_tool.wrench.force.z = tempData.at(2);
00385   raw_data_tool.wrench.torque.x = tempData.at(3);
00386   raw_data_tool.wrench.torque.y = tempData.at(4);
00387   raw_data_tool.wrench.torque.z = tempData.at(5);
00388 
00389   // Apply bias
00390   copyWrench(raw_data_tool, tf_data_tool, bias);
00391 
00392   // Copy in new netft data in tool frame and transform to world frame
00393   transformFrame(tf_data_tool, tf_data_world, 'w');
00394 
00395   // Apply thresholds
00396   applyThreshold(tf_data_world.wrench.force.x, threshold.wrench.force.x);
00397   applyThreshold(tf_data_world.wrench.force.y, threshold.wrench.force.y);
00398   applyThreshold(tf_data_world.wrench.force.z, threshold.wrench.force.z);
00399   applyThreshold(tf_data_world.wrench.torque.x, threshold.wrench.torque.x);
00400   applyThreshold(tf_data_world.wrench.torque.y, threshold.wrench.torque.y);
00401   applyThreshold(tf_data_world.wrench.torque.z, threshold.wrench.torque.z);
00402   applyThreshold(tf_data_tool.wrench.force.x, threshold.wrench.force.x);
00403   applyThreshold(tf_data_tool.wrench.force.y, threshold.wrench.force.y);
00404   applyThreshold(tf_data_tool.wrench.force.z, threshold.wrench.force.z);
00405   applyThreshold(tf_data_tool.wrench.torque.x, threshold.wrench.torque.x);
00406   applyThreshold(tf_data_tool.wrench.torque.y, threshold.wrench.torque.y);
00407   applyThreshold(tf_data_tool.wrench.torque.z, threshold.wrench.torque.z);
00408 
00409   // Publish data for debugging
00410   if(DEBUG_DATA)
00411     data_pub.publish(tf_data_tool);
00412   //ROS_INFO_STREAM("Callback time: " << tf_data_tool.header.stamp.toSec()-ros::Time::now().toSec());
00413 }
00414 
00415 bool NetftUtilsLean::biasSensor(bool toBias)
00416 {
00417   if(toBias)
00418   {
00419     if(!hasData)
00420     {
00421       geometry_msgs::WrenchStamped data;
00422       if(!ftTopic.empty())
00423       {
00424         ros::Time startTime = ros::Time::now();
00425         while(ros::Time::now().toSec()-startTime.toSec() < 0.1 && !hasData)
00426         {
00427           ros::Duration(0.01).sleep();
00428         }
00429         if(hasData)
00430         {
00431           data = raw_topic_data;
00432         }
00433         else
00434         {
00435           ROS_ERROR("Bias sensor failed.");
00436           return false;
00437         }
00438       }
00439       else
00440       {
00441         if (netft->waitForNewData())
00442         {
00443           netft->getData(data);
00444         }
00445         else
00446         {
00447           ROS_ERROR("Bias sensor failed.");
00448           return false;
00449         }
00450       }
00451       // Copy tool frame data.
00452       raw_data_tool.header.stamp = data.header.stamp;
00453       raw_data_tool.header.frame_id = ft_frame;
00454       raw_data_tool.wrench.force.x = -data.wrench.force.x;
00455       raw_data_tool.wrench.force.y = data.wrench.force.y;
00456       raw_data_tool.wrench.force.z = data.wrench.force.z;
00457       raw_data_tool.wrench.torque.x = -data.wrench.torque.x;
00458       raw_data_tool.wrench.torque.y = data.wrench.torque.y;
00459       raw_data_tool.wrench.torque.z = data.wrench.torque.z;
00460     }
00461     copyWrench(raw_data_tool, bias, zero_wrench);
00462     isNewBias = true;
00463   }
00464   else
00465   {
00466     copyWrench(zero_wrench, bias, zero_wrench);
00467   }
00468   isBiased = toBias;
00469   return true;
00470 }
00471 
00472 bool NetftUtilsLean::setFilter(bool toFilter, double deltaT, double cutoffFreq)
00473 {
00474   if(toFilter)
00475   {
00476     newFilter = true;
00477     isFilterOn = true;
00478     deltaTFilter = deltaT;
00479     cutoffFrequency = cutoffFreq;
00480   }
00481   else
00482   {
00483     isFilterOn = false;
00484   }
00485 
00486   return true;
00487 }
00488 
00489 bool NetftUtilsLean::setMax(double fMaxU, double tMaxU, double fMaxB, double tMaxB)
00490 {
00491   if(fMaxU >= 0.0001)
00492   {
00493     forceMaxU = fMaxU;
00494     torqueMaxU = tMaxU;
00495     forceMaxB = fMaxB;
00496     torqueMaxB = tMaxB;
00497     return true;
00498   }
00499   else
00500   {
00501     ROS_ERROR_STREAM("All maximum FT values must be positive.");
00502     return false;
00503   }
00504 }
00505 
00506 bool NetftUtilsLean::setThreshold(double fThresh, double tThresh)
00507 {
00508   threshold.wrench.force.x = fThresh;
00509   threshold.wrench.force.y = fThresh;
00510   threshold.wrench.force.z = fThresh;
00511   threshold.wrench.torque.x = tThresh;
00512   threshold.wrench.torque.y = tThresh;
00513   threshold.wrench.torque.z = tThresh;
00514 
00515   return true;
00516 }
00517 
00518 void NetftUtilsLean::checkMaxForce()
00519 {
00520   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);
00521   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);
00522   double fMax;
00523   double tMax;
00524   if(isBiased && !isNewBias)
00525   {
00526     if(forceMaxB > 0.001 && torqueMaxB > 0.001)
00527     {
00528       fMax = forceMaxB;
00529       tMax = torqueMaxB;
00530     }
00531     else
00532     {
00533       fMax = forceMaxU;
00534       tMax = torqueMaxU;
00535     }
00536   }
00537   else
00538   {
00539     if(isBiased && isNewBias)
00540     {
00541       isNewBias = false;
00542     }
00543     fMax = forceMaxU;
00544     tMax = torqueMaxU;
00545   }
00546 
00547   // If max FT exceeded, send cancel unless we have just sent it MAX_CANCEL times
00548   //ROS_INFO("FMAG: %f TMAG: %f", fMag, tMag);
00549   if((fabs(fMag) > fMax || fabs(tMag) > tMax) && cancel_count > 0)
00550   {
00551     cancel_msg.toCancel = true;
00552     //ROS_INFO("Force torque violation. Canceling move.");
00553     ROS_INFO("FMAG: %f FMAX: %f TMAG:%f TMAX: %f count: %d wait: %d", fMag, fMax, tMag, tMax, cancel_count, cancel_wait);
00554     cancel_count-=1;
00555   }
00556   // If we have sent cancel MAX_CANCEL times, don't send cancel again for MAX_WAIT cycles
00557   else if(cancel_count == 0 && cancel_wait > 0 && cancel_wait <= MAX_WAIT)
00558   {
00559     cancel_msg.toCancel = false;
00560     cancel_wait-=1;
00561   }
00562   // If we have just finished waiting MAX_WAIT times, or the max force is no longer exceeded, reset cancel_count and cancel_wait
00563   else if(cancel_wait == 0 || !(fabs(fMag) > fMax || fabs(tMag) > tMax))
00564   {
00565     cancel_msg.toCancel = false;
00566     cancel_count = MAX_CANCEL;
00567     cancel_wait = MAX_WAIT;
00568   }
00569 }
00570 
00571 void NetftUtilsLean::setFTAddress(std::string ftAd)
00572 {
00573   ftAddress = ftAd;
00574 }
00575 
00576 void NetftUtilsLean::setFTTopic(std::string ftTop)
00577 {
00578   ftTopic = ftTop;
00579 }
00580 
00581 void NetftUtilsLean::getRawData(geometry_msgs::WrenchStamped& data)
00582 {
00583   data = raw_data_tool;
00584 }
00585 
00586 void NetftUtilsLean::getToolData(geometry_msgs::WrenchStamped& data)
00587 {
00588   data = tf_data_tool;
00589 }
00590 
00591 void NetftUtilsLean::getWorldData(geometry_msgs::WrenchStamped& data)
00592 {
00593   data = tf_data_world;
00594 }
00595 
00596 bool NetftUtilsLean::isRunning()
00597 {
00598   return isActive;
00599 }
00600 


netft_utils
Author(s): Alex von Sternberg , Derek King, Andy Zelenak
autogenerated on Thu Jun 6 2019 20:11:15