#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 () |
Private Attributes | |
geometry_msgs::WrenchStamped | bias |
int | cancel_count |
netft_utils::Cancel | cancel_msg |
int | cancel_wait |
double | cutoffFrequency |
double | cycleRate |
ros::Publisher | data_pub |
double | deltaTFilter |
double | forceMaxB |
double | forceMaxU |
std::string | ft_frame |
ros::Subscriber | ft_sub |
tf::StampedTransform | ft_to_world |
std::string | ftAddress |
std::string | ftTopic |
bool | hasData |
bool | isActive |
bool | isBiased |
bool | isFilterOn |
bool | isInit |
bool | isNewBias |
tf::TransformListener * | listener |
LPFilter * | lp |
bool | lpExists |
std::future< bool > | monitorThread |
ros::NodeHandle * | n |
std::unique_ptr < netft_rdt_driver::NetFTRDTDriver > | netft |
ros::Publisher | netft_cancel_pub |
bool | newFilter |
geometry_msgs::WrenchStamped | raw_data_tool |
geometry_msgs::WrenchStamped | raw_topic_data |
geometry_msgs::WrenchStamped | tf_data_tool |
geometry_msgs::WrenchStamped | tf_data_world |
geometry_msgs::WrenchStamped | threshold |
bool | toMonitor |
double | torqueMaxB |
double | torqueMaxU |
bool | toUpdate |
std::future< bool > | updateThread |
bool | waitingForTransform |
std::string | world_frame |
geometry_msgs::WrenchStamped | zero_wrench |
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.
Definition at line 19 of file netft_utils_lean.cpp.
Definition at line 46 of file netft_utils_lean.cpp.
void NetftUtilsLean::applyThreshold | ( | double & | value, |
double | thresh | ||
) | [private] |
Definition at line 314 of file netft_utils_lean.cpp.
bool NetftUtilsLean::biasSensor | ( | bool | toBias | ) |
Definition at line 416 of file netft_utils_lean.cpp.
void NetftUtilsLean::checkMaxForce | ( | ) | [private] |
Definition at line 519 of file netft_utils_lean.cpp.
void NetftUtilsLean::copyWrench | ( | geometry_msgs::WrenchStamped & | in, |
geometry_msgs::WrenchStamped & | out, | ||
geometry_msgs::WrenchStamped & | bias | ||
) | [private] |
Definition at line 302 of file netft_utils_lean.cpp.
void NetftUtilsLean::dataCallback | ( | const geometry_msgs::WrenchStamped::ConstPtr & | msg | ) | [private] |
Definition at line 190 of file netft_utils_lean.cpp.
void NetftUtilsLean::getRawData | ( | geometry_msgs::WrenchStamped & | data | ) |
Definition at line 582 of file netft_utils_lean.cpp.
void NetftUtilsLean::getToolData | ( | geometry_msgs::WrenchStamped & | data | ) |
Definition at line 587 of file netft_utils_lean.cpp.
void NetftUtilsLean::getWorldData | ( | geometry_msgs::WrenchStamped & | data | ) |
Definition at line 592 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 204 of file netft_utils_lean.cpp.
bool NetftUtilsLean::isRunning | ( | ) |
Definition at line 597 of file netft_utils_lean.cpp.
bool NetftUtilsLean::monitorData | ( | ) | [private] |
Definition at line 159 of file netft_utils_lean.cpp.
void NetftUtilsLean::netftCallback | ( | const geometry_msgs::WrenchStamped & | data | ) | [private] |
Definition at line 353 of file netft_utils_lean.cpp.
bool NetftUtilsLean::run | ( | ) |
Definition at line 120 of file netft_utils_lean.cpp.
bool NetftUtilsLean::setFilter | ( | bool | toFilter, |
double | deltaT, | ||
double | cutoffFreq | ||
) |
Definition at line 473 of file netft_utils_lean.cpp.
void NetftUtilsLean::setFTAddress | ( | std::string | ftAddress | ) |
Definition at line 572 of file netft_utils_lean.cpp.
void NetftUtilsLean::setFTTopic | ( | std::string | ftTopic | ) |
Definition at line 577 of file netft_utils_lean.cpp.
bool NetftUtilsLean::setMax | ( | double | fMaxU, |
double | tMaxU, | ||
double | fMaxB, | ||
double | tMaxB | ||
) |
Definition at line 490 of file netft_utils_lean.cpp.
bool NetftUtilsLean::setThreshold | ( | double | fThresh, |
double | tThresh | ||
) |
Definition at line 507 of file netft_utils_lean.cpp.
bool NetftUtilsLean::setUserInput | ( | std::string | world, |
std::string | ft, | ||
double | force, | ||
double | torque | ||
) |
Definition at line 219 of file netft_utils_lean.cpp.
void NetftUtilsLean::stop | ( | ) |
Definition at line 153 of file netft_utils_lean.cpp.
void NetftUtilsLean::transformFrame | ( | geometry_msgs::WrenchStamped | in_data, |
geometry_msgs::WrenchStamped & | out_data, | ||
char | target_frame | ||
) | [private] |
Definition at line 322 of file netft_utils_lean.cpp.
bool NetftUtilsLean::update | ( | ) | [private] |
Definition at line 256 of file netft_utils_lean.cpp.
bool NetftUtilsLean::waitForData | ( | double | timeout | ) |
Definition at line 209 of file netft_utils_lean.cpp.
geometry_msgs::WrenchStamped NetftUtilsLean::bias [private] |
Definition at line 75 of file netft_utils_lean.h.
int NetftUtilsLean::cancel_count [private] |
Definition at line 92 of file netft_utils_lean.h.
netft_utils::Cancel NetftUtilsLean::cancel_msg [private] |
Definition at line 89 of file netft_utils_lean.h.
int NetftUtilsLean::cancel_wait [private] |
Definition at line 93 of file netft_utils_lean.h.
double NetftUtilsLean::cutoffFrequency [private] |
Definition at line 64 of file netft_utils_lean.h.
double NetftUtilsLean::cycleRate [private] |
Definition at line 58 of file netft_utils_lean.h.
ros::Publisher NetftUtilsLean::data_pub [private] |
Definition at line 104 of file netft_utils_lean.h.
const bool NetftUtilsLean::DEBUG_DATA = true [static, private] |
Definition at line 125 of file netft_utils_lean.h.
double NetftUtilsLean::deltaTFilter [private] |
Definition at line 63 of file netft_utils_lean.h.
double NetftUtilsLean::forceMaxB [private] |
Definition at line 94 of file netft_utils_lean.h.
double NetftUtilsLean::forceMaxU [private] |
Definition at line 96 of file netft_utils_lean.h.
std::string NetftUtilsLean::ft_frame [private] |
Definition at line 72 of file netft_utils_lean.h.
ros::Subscriber NetftUtilsLean::ft_sub [private] |
Definition at line 100 of file netft_utils_lean.h.
Definition at line 70 of file netft_utils_lean.h.
std::string NetftUtilsLean::ftAddress [private] |
Definition at line 49 of file netft_utils_lean.h.
std::string NetftUtilsLean::ftTopic [private] |
Definition at line 50 of file netft_utils_lean.h.
bool NetftUtilsLean::hasData [private] |
Definition at line 52 of file netft_utils_lean.h.
bool NetftUtilsLean::isActive [private] |
Definition at line 86 of file netft_utils_lean.h.
bool NetftUtilsLean::isBiased [private] |
Definition at line 83 of file netft_utils_lean.h.
bool NetftUtilsLean::isFilterOn [private] |
Definition at line 62 of file netft_utils_lean.h.
bool NetftUtilsLean::isInit [private] |
Definition at line 51 of file netft_utils_lean.h.
bool NetftUtilsLean::isNewBias [private] |
Definition at line 84 of file netft_utils_lean.h.
tf::TransformListener* NetftUtilsLean::listener [private] |
Definition at line 69 of file netft_utils_lean.h.
LPFilter* NetftUtilsLean::lp [private] |
Definition at line 61 of file netft_utils_lean.h.
bool NetftUtilsLean::lpExists [private] |
Definition at line 66 of file netft_utils_lean.h.
const int NetftUtilsLean::MAX_CANCEL = 5 [static, private] |
Definition at line 90 of file netft_utils_lean.h.
const int NetftUtilsLean::MAX_WAIT = 100 [static, private] |
Definition at line 91 of file netft_utils_lean.h.
std::future<bool> NetftUtilsLean::monitorThread [private] |
Definition at line 111 of file netft_utils_lean.h.
ros::NodeHandle* NetftUtilsLean::n [private] |
Definition at line 46 of file netft_utils_lean.h.
std::unique_ptr<netft_rdt_driver::NetFTRDTDriver> NetftUtilsLean::netft [private] |
Definition at line 55 of file netft_utils_lean.h.
Definition at line 103 of file netft_utils_lean.h.
bool NetftUtilsLean::newFilter [private] |
Definition at line 65 of file netft_utils_lean.h.
geometry_msgs::WrenchStamped NetftUtilsLean::raw_data_tool [private] |
Definition at line 76 of file netft_utils_lean.h.
geometry_msgs::WrenchStamped NetftUtilsLean::raw_topic_data [private] |
Definition at line 81 of file netft_utils_lean.h.
geometry_msgs::WrenchStamped NetftUtilsLean::tf_data_tool [private] |
Definition at line 78 of file netft_utils_lean.h.
geometry_msgs::WrenchStamped NetftUtilsLean::tf_data_world [private] |
Definition at line 77 of file netft_utils_lean.h.
geometry_msgs::WrenchStamped NetftUtilsLean::threshold [private] |
Definition at line 80 of file netft_utils_lean.h.
bool NetftUtilsLean::toMonitor [private] |
Definition at line 114 of file netft_utils_lean.h.
double NetftUtilsLean::torqueMaxB [private] |
Definition at line 95 of file netft_utils_lean.h.
double NetftUtilsLean::torqueMaxU [private] |
Definition at line 97 of file netft_utils_lean.h.
bool NetftUtilsLean::toUpdate [private] |
Definition at line 113 of file netft_utils_lean.h.
std::future<bool> NetftUtilsLean::updateThread [private] |
Definition at line 112 of file netft_utils_lean.h.
bool NetftUtilsLean::waitingForTransform [private] |
Definition at line 85 of file netft_utils_lean.h.
std::string NetftUtilsLean::world_frame [private] |
Definition at line 71 of file netft_utils_lean.h.
geometry_msgs::WrenchStamped NetftUtilsLean::zero_wrench [private] |
Definition at line 79 of file netft_utils_lean.h.