#include <netft_utils_lean.h>
Public Member Functions | |
bool | biasSensor (bool toBias) |
void | getRawData (geometry_msgs::WrenchStamped &data) |
void | getToolData (geometry_msgs::WrenchStamped &data) |
void | getWorldData (geometry_msgs::WrenchStamped &data) |
bool | initialize (double rate, std::string world, std::string ft, double force=60.0, double torque=6.0) |
bool | isReady () |
bool | isRunning () |
NetftUtilsLean (ros::NodeHandle *nh) | |
bool | run () |
bool | setFilter (bool toFilter, double deltaT, double cutoffFreq) |
void | setFTAddress (std::string ftAddress) |
void | setFTTopic (std::string ftTopic) |
bool | setMax (double fMaxU, double tMaxU, double fMaxB, double tMaxB) |
bool | setThreshold (double fThresh, double tThresh) |
bool | setUserInput (std::string world, std::string ft, double force, double torque) |
void | stop () |
bool | waitForData (double timeout) |
~NetftUtilsLean () | |
Private Member Functions | |
void | applyThreshold (double &value, double thresh) |
void | checkMaxForce () |
void | copyWrench (geometry_msgs::WrenchStamped &in, geometry_msgs::WrenchStamped &out, geometry_msgs::WrenchStamped &bias) |
void | dataCallback (const geometry_msgs::WrenchStamped::ConstPtr &msg) |
bool | monitorData () |
void | netftCallback (const geometry_msgs::WrenchStamped &data) |
void | transformFrame (geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data, char target_frame) |
bool | update () |
Static Private Attributes | |
static const bool | DEBUG_DATA = true |
static const int | MAX_CANCEL = 5 |
static const int | MAX_WAIT = 100 |
This program takes force/torque data and applies transforms to usable data
Definition at line 19 of file netft_utils_lean.h.
NetftUtilsLean::NetftUtilsLean | ( | ros::NodeHandle * | nh | ) |
Definition at line 19 of file netft_utils_lean.cpp.
NetftUtilsLean::~NetftUtilsLean | ( | ) |
Definition at line 46 of file netft_utils_lean.cpp.
|
private |
Definition at line 313 of file netft_utils_lean.cpp.
bool NetftUtilsLean::biasSensor | ( | bool | toBias | ) |
Definition at line 415 of file netft_utils_lean.cpp.
|
private |
Definition at line 518 of file netft_utils_lean.cpp.
|
private |
Definition at line 301 of file netft_utils_lean.cpp.
|
private |
Definition at line 189 of file netft_utils_lean.cpp.
void NetftUtilsLean::getRawData | ( | geometry_msgs::WrenchStamped & | data | ) |
Definition at line 581 of file netft_utils_lean.cpp.
void NetftUtilsLean::getToolData | ( | geometry_msgs::WrenchStamped & | data | ) |
Definition at line 586 of file netft_utils_lean.cpp.
void NetftUtilsLean::getWorldData | ( | geometry_msgs::WrenchStamped & | data | ) |
Definition at line 591 of file netft_utils_lean.cpp.
bool NetftUtilsLean::initialize | ( | double | rate, |
std::string | world, | ||
std::string | ft, | ||
double | force = 60.0 , |
||
double | torque = 6.0 |
||
) |
Definition at line 53 of file netft_utils_lean.cpp.
bool NetftUtilsLean::isReady | ( | ) |
Definition at line 203 of file netft_utils_lean.cpp.
bool NetftUtilsLean::isRunning | ( | ) |
Definition at line 596 of file netft_utils_lean.cpp.
|
private |
Definition at line 158 of file netft_utils_lean.cpp.
|
private |
Definition at line 352 of file netft_utils_lean.cpp.
bool NetftUtilsLean::run | ( | ) |
Definition at line 119 of file netft_utils_lean.cpp.
bool NetftUtilsLean::setFilter | ( | bool | toFilter, |
double | deltaT, | ||
double | cutoffFreq | ||
) |
Definition at line 472 of file netft_utils_lean.cpp.
void NetftUtilsLean::setFTAddress | ( | std::string | ftAddress | ) |
Definition at line 571 of file netft_utils_lean.cpp.
void NetftUtilsLean::setFTTopic | ( | std::string | ftTopic | ) |
Definition at line 576 of file netft_utils_lean.cpp.
bool NetftUtilsLean::setMax | ( | double | fMaxU, |
double | tMaxU, | ||
double | fMaxB, | ||
double | tMaxB | ||
) |
Definition at line 489 of file netft_utils_lean.cpp.
bool NetftUtilsLean::setThreshold | ( | double | fThresh, |
double | tThresh | ||
) |
Definition at line 506 of file netft_utils_lean.cpp.
bool NetftUtilsLean::setUserInput | ( | std::string | world, |
std::string | ft, | ||
double | force, | ||
double | torque | ||
) |
Definition at line 218 of file netft_utils_lean.cpp.
void NetftUtilsLean::stop | ( | ) |
Definition at line 152 of file netft_utils_lean.cpp.
|
private |
Definition at line 321 of file netft_utils_lean.cpp.
|
private |
Definition at line 255 of file netft_utils_lean.cpp.
bool NetftUtilsLean::waitForData | ( | double | timeout | ) |
Definition at line 208 of file netft_utils_lean.cpp.
|
private |
Definition at line 75 of file netft_utils_lean.h.
|
private |
Definition at line 92 of file netft_utils_lean.h.
|
private |
Definition at line 89 of file netft_utils_lean.h.
|
private |
Definition at line 93 of file netft_utils_lean.h.
|
private |
Definition at line 64 of file netft_utils_lean.h.
|
private |
Definition at line 58 of file netft_utils_lean.h.
|
private |
Definition at line 104 of file netft_utils_lean.h.
|
staticprivate |
Definition at line 125 of file netft_utils_lean.h.
|
private |
Definition at line 63 of file netft_utils_lean.h.
|
private |
Definition at line 94 of file netft_utils_lean.h.
|
private |
Definition at line 96 of file netft_utils_lean.h.
|
private |
Definition at line 72 of file netft_utils_lean.h.
|
private |
Definition at line 100 of file netft_utils_lean.h.
|
private |
Definition at line 70 of file netft_utils_lean.h.
|
private |
Definition at line 49 of file netft_utils_lean.h.
|
private |
Definition at line 50 of file netft_utils_lean.h.
|
private |
Definition at line 52 of file netft_utils_lean.h.
|
private |
Definition at line 86 of file netft_utils_lean.h.
|
private |
Definition at line 83 of file netft_utils_lean.h.
|
private |
Definition at line 62 of file netft_utils_lean.h.
|
private |
Definition at line 51 of file netft_utils_lean.h.
|
private |
Definition at line 84 of file netft_utils_lean.h.
|
private |
Definition at line 69 of file netft_utils_lean.h.
|
private |
Definition at line 61 of file netft_utils_lean.h.
|
private |
Definition at line 66 of file netft_utils_lean.h.
|
staticprivate |
Definition at line 90 of file netft_utils_lean.h.
|
staticprivate |
Definition at line 91 of file netft_utils_lean.h.
|
private |
Definition at line 111 of file netft_utils_lean.h.
|
private |
Definition at line 46 of file netft_utils_lean.h.
|
private |
Definition at line 55 of file netft_utils_lean.h.
|
private |
Definition at line 103 of file netft_utils_lean.h.
|
private |
Definition at line 65 of file netft_utils_lean.h.
|
private |
Definition at line 76 of file netft_utils_lean.h.
|
private |
Definition at line 81 of file netft_utils_lean.h.
|
private |
Definition at line 78 of file netft_utils_lean.h.
|
private |
Definition at line 77 of file netft_utils_lean.h.
|
private |
Definition at line 80 of file netft_utils_lean.h.
|
private |
Definition at line 114 of file netft_utils_lean.h.
|
private |
Definition at line 95 of file netft_utils_lean.h.
|
private |
Definition at line 97 of file netft_utils_lean.h.
|
private |
Definition at line 113 of file netft_utils_lean.h.
|
private |
Definition at line 112 of file netft_utils_lean.h.
|
private |
Definition at line 85 of file netft_utils_lean.h.
|
private |
Definition at line 71 of file netft_utils_lean.h.
|
private |
Definition at line 79 of file netft_utils_lean.h.