1 #ifndef NET_FT_UTILS_LEAN_H 2 #define NET_FT_UTILS_LEAN_H 5 #include "std_msgs/String.h" 7 #include "geometry_msgs/WrenchStamped.h" 8 #include "netft_utils/Cancel.h" 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);
32 bool setMax(
double fMaxU,
double tMaxU,
double fMaxB,
double tMaxB);
34 bool setFilter(
bool toFilter,
double deltaT,
double cutoffFreq);
38 void getToolData(geometry_msgs::WrenchStamped& data);
39 void getRawData(geometry_msgs::WrenchStamped& data);
55 std::unique_ptr<netft_rdt_driver::NetFTRDTDriver>
netft;
75 geometry_msgs::WrenchStamped
bias;
107 void netftCallback(
const geometry_msgs::WrenchStamped& data);
108 void dataCallback(
const geometry_msgs::WrenchStamped::ConstPtr& msg);
119 void copyWrench(geometry_msgs::WrenchStamped &in, geometry_msgs::WrenchStamped &out, geometry_msgs::WrenchStamped &bias);
121 void transformFrame(geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data,
char target_frame);
tf::StampedTransform ft_to_world
void transformFrame(geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data, char target_frame)
bool biasSensor(bool toBias)
ros::Publisher netft_cancel_pub
void setFTTopic(std::string ftTopic)
std::unique_ptr< netft_rdt_driver::NetFTRDTDriver > netft
std::future< bool > monitorThread
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
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)
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)
bool setThreshold(double fThresh, double tThresh)
bool waitForData(double timeout)
static const int MAX_WAIT
void netftCallback(const geometry_msgs::WrenchStamped &data)