33 waitingForTransform(true),
35 cancel_count(MAX_CANCEL),
36 cancel_wait(MAX_WAIT),
75 ROS_INFO_STREAM(
"Using NETFT topic instead of IP because ftTopic is:" << ftTopic);
83 catch(std::runtime_error)
168 if (
netft->waitForNewData())
171 geometry_msgs::WrenchStamped
data;
173 netft->getData(data);
220 if(world.compare(
"") == 0)
227 if(ft.compare(
"") == 0)
259 ROS_ERROR_STREAM(
"Cannot update until NetftUtilsLean is initialized properly.");
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;
315 if(value <= thresh && value >= -thresh)
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')
337 else if(target_frame ==
't')
339 out_data.header.frame_id =
ft_frame;
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();
355 std::vector<double> tempData;
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;
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;
421 geometry_msgs::WrenchStamped
data;
441 if (
netft->waitForNewData())
443 netft->getData(data);
549 if((fabs(fMag) > fMax || fabs(tMag) > tMax) &&
cancel_count > 0)
563 else if(
cancel_wait == 0 || !(fabs(fMag) > fMax || fabs(tMag) > tMax))
tf::StampedTransform ft_to_world
void transformFrame(geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data, char target_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)
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)
std::unique_ptr< netft_rdt_driver::NetFTRDTDriver > netft
TFSIMD_FORCE_INLINE void setZ(tfScalar z)
std::future< bool > monitorThread
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
void setFTAddress(std::string ftAddress)
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)
static const bool DEBUG_DATA
static const int MAX_CANCEL
bool setFilter(bool toFilter, double deltaT, double cutoffFreq)
geometry_msgs::WrenchStamped tf_data_tool
std::future< bool > updateThread
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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)
geometry_msgs::WrenchStamped bias
TFSIMD_FORCE_INLINE const tfScalar & getX() const
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)
bool setThreshold(double fThresh, double tThresh)
bool waitForData(double timeout)
static const int MAX_WAIT
void netftCallback(const geometry_msgs::WrenchStamped &data)