Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
NetftUtils Class Reference

#include <netft_utils.h>

List of all members.

Public Member Functions

void initialize ()
 NetftUtils (ros::NodeHandle nh)
void setUserInput (std::string world, std::string ft, double force, double torque)
void update ()
 ~NetftUtils ()

Private Member Functions

void applyThreshold (double &value, double thresh)
void checkMaxForce ()
bool compensateForGravity (netft_utils::SetBias::Request &req, netft_utils::SetBias::Response &res)
void copyWrench (geometry_msgs::WrenchStamped &in, geometry_msgs::WrenchStamped &out, geometry_msgs::WrenchStamped &bias)
bool fixedOrientationBias (netft_utils::SetBias::Request &req, netft_utils::SetBias::Response &res)
bool getWeight (netft_utils::GetDouble::Request &req, netft_utils::GetDouble::Response &res)
void netftCallback (const geometry_msgs::WrenchStamped::ConstPtr &data)
bool setFilter (netft_utils::SetFilter::Request &req, netft_utils::SetFilter::Response &res)
bool setMax (netft_utils::SetMax::Request &req, netft_utils::SetMax::Response &res)
bool setThreshold (netft_utils::SetThreshold::Request &req, netft_utils::SetThreshold::Response &res)
bool setWeightBias (netft_utils::SetBias::Request &req, netft_utils::SetBias::Response &res)
void transformFrame (geometry_msgs::WrenchStamped in_data, geometry_msgs::WrenchStamped &out_data, char target_frame)

Private Attributes

geometry_msgs::WrenchStamped bias
ros::ServiceServer bias_service
int cancel_count
netft_utils::Cancel cancel_msg
int cancel_wait
double cutoffFrequency
double deltaTFilter
ros::ServiceServer filter_service
double forceMaxB
double forceMaxU
std::string ft_frame
tf::StampedTransform ft_to_world
ros::ServiceServer get_weight_service
ros::ServiceServer gravity_comp_service
bool isBiased
bool isFilterOn
bool isGravityBiased
bool isNewBias
bool isNewGravityBias
tf::TransformListenerlistener
LPFilterlp
ros::NodeHandle n
ros::Publisher netft_cancel_pub
ros::Publisher netft_raw_world_data_pub
ros::Publisher netft_tool_data_pub
ros::Publisher netft_world_data_pub
bool newFilter
double payloadLeverArm
double payloadWeight
ros::Subscriber raw_data_sub
geometry_msgs::WrenchStamped raw_data_tool
geometry_msgs::WrenchStamped raw_data_world
ros::ServiceServer set_max_service
geometry_msgs::WrenchStamped tf_data_tool
geometry_msgs::WrenchStamped tf_data_world
ros::ServiceServer theshold_service
geometry_msgs::WrenchStamped threshold
double torqueMaxB
double torqueMaxU
geometry_msgs::WrenchStamped weight_bias
ros::ServiceServer weight_bias_service
std::string world_frame
geometry_msgs::WrenchStamped zero_wrench

Static Private Attributes

static const int MAX_CANCEL = 5
static const int MAX_WAIT = 100

Detailed Description

This program takes force/torque data and applies transforms to usable data

Definition at line 22 of file netft_utils.h.


Constructor & Destructor Documentation

Definition at line 73 of file netft_utils.cpp.

Definition at line 94 of file netft_utils.cpp.


Member Function Documentation

void NetftUtils::applyThreshold ( double &  value,
double  thresh 
) [private]

Definition at line 199 of file netft_utils.cpp.

void NetftUtils::checkMaxForce ( ) [private]

Definition at line 445 of file netft_utils.cpp.

bool NetftUtils::compensateForGravity ( netft_utils::SetBias::Request &  req,
netft_utils::SetBias::Response &  res 
) [private]

Definition at line 349 of file netft_utils.cpp.

void NetftUtils::copyWrench ( geometry_msgs::WrenchStamped &  in,
geometry_msgs::WrenchStamped &  out,
geometry_msgs::WrenchStamped &  bias 
) [private]

Definition at line 187 of file netft_utils.cpp.

bool NetftUtils::fixedOrientationBias ( netft_utils::SetBias::Request &  req,
netft_utils::SetBias::Response &  res 
) [private]

Definition at line 322 of file netft_utils.cpp.

bool NetftUtils::getWeight ( netft_utils::GetDouble::Request &  req,
netft_utils::GetDouble::Response &  res 
) [private]

Definition at line 422 of file netft_utils.cpp.

Definition at line 100 of file netft_utils.cpp.

void NetftUtils::netftCallback ( const geometry_msgs::WrenchStamped::ConstPtr &  data) [private]

Definition at line 239 of file netft_utils.cpp.

bool NetftUtils::setFilter ( netft_utils::SetFilter::Request &  req,
netft_utils::SetFilter::Response &  res 
) [private]

Definition at line 379 of file netft_utils.cpp.

bool NetftUtils::setMax ( netft_utils::SetMax::Request &  req,
netft_utils::SetMax::Response &  res 
) [private]

Definition at line 396 of file netft_utils.cpp.

bool NetftUtils::setThreshold ( netft_utils::SetThreshold::Request &  req,
netft_utils::SetThreshold::Response &  res 
) [private]

Definition at line 431 of file netft_utils.cpp.

void NetftUtils::setUserInput ( std::string  world,
std::string  ft,
double  force,
double  torque 
)

Definition at line 137 of file netft_utils.cpp.

bool NetftUtils::setWeightBias ( netft_utils::SetBias::Request &  req,
netft_utils::SetBias::Response &  res 
) [private]

Definition at line 407 of file netft_utils.cpp.

void NetftUtils::transformFrame ( geometry_msgs::WrenchStamped  in_data,
geometry_msgs::WrenchStamped &  out_data,
char  target_frame 
) [private]

Definition at line 207 of file netft_utils.cpp.

Definition at line 151 of file netft_utils.cpp.


Member Data Documentation

geometry_msgs::WrenchStamped NetftUtils::bias [private]

Definition at line 50 of file netft_utils.h.

Definition at line 90 of file netft_utils.h.

int NetftUtils::cancel_count [private]

Definition at line 71 of file netft_utils.h.

netft_utils::Cancel NetftUtils::cancel_msg [private]

Definition at line 68 of file netft_utils.h.

int NetftUtils::cancel_wait [private]

Definition at line 72 of file netft_utils.h.

double NetftUtils::cutoffFrequency [private]

Definition at line 40 of file netft_utils.h.

double NetftUtils::deltaTFilter [private]

Definition at line 39 of file netft_utils.h.

Definition at line 96 of file netft_utils.h.

double NetftUtils::forceMaxB [private]

Definition at line 73 of file netft_utils.h.

double NetftUtils::forceMaxU [private]

Definition at line 75 of file netft_utils.h.

std::string NetftUtils::ft_frame [private]

Definition at line 47 of file netft_utils.h.

Definition at line 45 of file netft_utils.h.

Definition at line 95 of file netft_utils.h.

Definition at line 91 of file netft_utils.h.

bool NetftUtils::isBiased [private]

Definition at line 62 of file netft_utils.h.

bool NetftUtils::isFilterOn [private]

Definition at line 38 of file netft_utils.h.

Definition at line 65 of file netft_utils.h.

bool NetftUtils::isNewBias [private]

Definition at line 63 of file netft_utils.h.

Definition at line 64 of file netft_utils.h.

Definition at line 44 of file netft_utils.h.

Definition at line 37 of file netft_utils.h.

const int NetftUtils::MAX_CANCEL = 5 [static, private]

Definition at line 69 of file netft_utils.h.

const int NetftUtils::MAX_WAIT = 100 [static, private]

Definition at line 70 of file netft_utils.h.

Definition at line 34 of file netft_utils.h.

Definition at line 85 of file netft_utils.h.

Definition at line 82 of file netft_utils.h.

Definition at line 84 of file netft_utils.h.

Definition at line 83 of file netft_utils.h.

bool NetftUtils::newFilter [private]

Definition at line 41 of file netft_utils.h.

double NetftUtils::payloadLeverArm [private]

Definition at line 60 of file netft_utils.h.

double NetftUtils::payloadWeight [private]

Definition at line 59 of file netft_utils.h.

Definition at line 79 of file netft_utils.h.

geometry_msgs::WrenchStamped NetftUtils::raw_data_tool [private]

Definition at line 53 of file netft_utils.h.

geometry_msgs::WrenchStamped NetftUtils::raw_data_world [private]

Definition at line 52 of file netft_utils.h.

Definition at line 92 of file netft_utils.h.

geometry_msgs::WrenchStamped NetftUtils::tf_data_tool [private]

Definition at line 55 of file netft_utils.h.

geometry_msgs::WrenchStamped NetftUtils::tf_data_world [private]

Definition at line 54 of file netft_utils.h.

Definition at line 93 of file netft_utils.h.

geometry_msgs::WrenchStamped NetftUtils::threshold [private]

Definition at line 57 of file netft_utils.h.

double NetftUtils::torqueMaxB [private]

Definition at line 74 of file netft_utils.h.

double NetftUtils::torqueMaxU [private]

Definition at line 76 of file netft_utils.h.

geometry_msgs::WrenchStamped NetftUtils::weight_bias [private]

Definition at line 51 of file netft_utils.h.

Definition at line 94 of file netft_utils.h.

std::string NetftUtils::world_frame [private]

Definition at line 46 of file netft_utils.h.

geometry_msgs::WrenchStamped NetftUtils::zero_wrench [private]

Definition at line 56 of file netft_utils.h.


The documentation for this class was generated from the following files:


netft_utils
Author(s): Alex von Sternberg , Derek King, Andy Zelenak
autogenerated on Sat Jul 15 2017 02:45:58