netft_utils_lean.h
Go to the documentation of this file.
1 #ifndef NET_FT_UTILS_LEAN_H
2 #define NET_FT_UTILS_LEAN_H
3 
4 #include "ros/ros.h"
5 #include "std_msgs/String.h"
7 #include "geometry_msgs/WrenchStamped.h"
8 #include "netft_utils/Cancel.h"
9 #include "lpfilter.h"
10 #include <math.h>
11 #include "netft_rdt_driver.h"
12 #include <memory>
13 #include <future>
14 
20 {
21 public:
24 
25  bool initialize(double rate, std::string world, std::string ft, double force = 60.0, double torque = 6.0);
26  bool setUserInput(std::string world, std::string ft, double force, double torque);
27  bool run();
28  void stop();
29 
30  // Access methods
31  bool biasSensor(bool toBias);
32  bool setMax(double fMaxU, double tMaxU, double fMaxB, double tMaxB);
33  bool setThreshold(double fThresh, double tThresh);
34  bool setFilter(bool toFilter, double deltaT, double cutoffFreq);
35  bool isReady();
36  bool waitForData(double timeout);
37  void getWorldData(geometry_msgs::WrenchStamped& data);
38  void getToolData(geometry_msgs::WrenchStamped& data);
39  void getRawData(geometry_msgs::WrenchStamped& data);
40  bool isRunning();
41  void setFTAddress(std::string ftAddress);
42  void setFTTopic(std::string ftTopic);
43 
44 private:
45  //Node handle
46  ros::NodeHandle* n; // ROS node handle
47 
48  // Initialization
49  std::string ftAddress;
50  std::string ftTopic;
51  bool isInit;
52  bool hasData;
53 
54  //netft class
55  std::unique_ptr<netft_rdt_driver::NetFTRDTDriver> netft;
56 
57  // cycle rate
58  double cycleRate;
59 
60  //LPFilter
61  LPFilter* lp; // Filter
62  bool isFilterOn;
63  double deltaTFilter;
65  bool newFilter;
66  bool lpExists;
67 
68  // Transform listener
70  tf::StampedTransform ft_to_world; // Transform from ft frame to world frame
71  std::string world_frame;
72  std::string ft_frame;
73 
74  // Wrenches used to hold force/torque and bias data
75  geometry_msgs::WrenchStamped bias; // Wrench containing the current bias data in tool frame
76  geometry_msgs::WrenchStamped raw_data_tool; // Wrench containing the current raw data from the netft sensor in the tool frame
77  geometry_msgs::WrenchStamped tf_data_world; // Wrench containing the transformed (world frame) data with bias and threshold applied
78  geometry_msgs::WrenchStamped tf_data_tool; // Wrench containing the transformed (tool frame) data with bias and threshold applied
79  geometry_msgs::WrenchStamped zero_wrench; // Wrench of all zeros for convenience
80  geometry_msgs::WrenchStamped threshold; // Wrench containing thresholds
81  geometry_msgs::WrenchStamped raw_topic_data; // Wrench containing raw topic data
82 
83  bool isBiased; // True if sensor is biased
84  bool isNewBias; // True if sensor was biased this pass
85  bool waitingForTransform; // False after initial transform is supplied
86  bool isActive; // True if run function has been called
87 
88  // Variables used to monitor FT violation and send a cancel move message
89  netft_utils::Cancel cancel_msg;
90  static const int MAX_CANCEL = 5; // Number of times to send cancel message when max force is exceeded
91  static const int MAX_WAIT = 100; // Number of cycles to wait after cancel message before sending again
92  int cancel_count; // Counter for times to send cancel message when max force is exceeded
93  int cancel_wait; // Counter of cycles to wait after cancel message before sending again
94  double forceMaxB; // Default max force limit to send cancel when FT is biased
95  double torqueMaxB; // Default max torque limit to send cancel when FT is biased
96  double forceMaxU; // Default max force limit to send cancel when FT is unbiased
97  double torqueMaxU; // Default max torque limit to send cancel when FT is unbiased
98 
99  // ROS subscribers
101 
102  // ROS publishers
105 
106  // Callback methods
107  void netftCallback(const geometry_msgs::WrenchStamped& data);
108  void dataCallback(const geometry_msgs::WrenchStamped::ConstPtr& msg);
109 
110  // Threads
111  std::future<bool> monitorThread;
112  std::future<bool> updateThread;
113  bool toUpdate;
114  bool toMonitor;
115 
116  bool update();
117 
118  // Convenience methods
119  void copyWrench(geometry_msgs::WrenchStamped &in, geometry_msgs::WrenchStamped &out, geometry_msgs::WrenchStamped &bias);
120  void applyThreshold(double &value, double thresh);
121  void transformFrame(geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data, char target_frame);
122  void checkMaxForce();
123  bool monitorData();
124 
125  static const bool DEBUG_DATA = true;
126 };
127 
128 #endif
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)
ros::Publisher netft_cancel_pub
void setFTTopic(std::string ftTopic)
std::unique_ptr< netft_rdt_driver::NetFTRDTDriver > netft
std::string ftAddress
std::future< bool > monitorThread
data
geometry_msgs::WrenchStamped raw_topic_data
geometry_msgs::WrenchStamped raw_data_tool
bool setMax(double fMaxU, double tMaxU, double fMaxB, double tMaxB)
geometry_msgs::WrenchStamped threshold
void applyThreshold(double &value, double thresh)
tf::TransformListener * listener
ros::Publisher data_pub
std::string ftTopic
void setFTAddress(std::string ftAddress)
geometry_msgs::WrenchStamped tf_data_world
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
bool setUserInput(std::string world, std::string ft, double force, double torque)
netft_utils::Cancel cancel_msg
NetftUtilsLean(ros::NodeHandle *nh)
ros::Subscriber ft_sub
geometry_msgs::WrenchStamped bias
geometry_msgs::WrenchStamped zero_wrench
void getRawData(geometry_msgs::WrenchStamped &data)
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
std::string world_frame
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