Public Member Functions | Private Member Functions | Private Attributes | List of all members
thormang3::ATIForceTorqueSensorTWE Class Reference

#include <ati_force_torque_sensor_twe.h>

Public Member Functions

 ATIForceTorqueSensorTWE ()
 
Eigen::MatrixXd getCurrentForceTorqueRaw ()
 
void getCurrentForceTorqueRaw (double *force_x_N, double *force_y_N, double *force_z_N, double *torque_x_Nm, double *torque_y_Nm, double *torque_z_Nm)
 
Eigen::MatrixXd getCurrentForceTorqueScaled ()
 
void getCurrentForceTorqueScaled (double *force_x_N, double *force_y_N, double *force_z_N, double *torque_x_Nm, double *torque_y_Nm, double *torque_z_Nm)
 
bool initialize (const std::string &ft_data_path, const std::string &ft_data_key, const std::string &ft_frame_id, const std::string &ft_raw_publish_name, const std::string &ft_scaled_publish_name)
 
void setCurrentVoltageOutput (double voltage0, double voltage1, double voltage2, double voltage3, double voltage4, double voltage5)
 
void setCurrentVoltageOutput (Eigen::MatrixXd voltage)
 
void setCurrentVoltageOutputPublish (double voltage0, double voltage1, double voltage2, double voltage3, double voltage4, double voltage5)
 
void setCurrentVoltageOutputPublish (Eigen::MatrixXd voltage)
 
void setNullForceTorque (Eigen::MatrixXd _ft_null)
 
void setScaleFactror (double ft_scale_factor)
 
void setScaleParam (double ft_scale_factor, Eigen::MatrixXd ft_null)
 
 ~ATIForceTorqueSensorTWE ()
 

Private Member Functions

bool parseFTData (const std::string &ft_data_path, const std::string &ft_data_key)
 

Private Attributes

Eigen::MatrixXd ft_coeff_mat_
 
Eigen::MatrixXd ft_current_volatge_
 
std::string ft_frame_id_
 
Eigen::MatrixXd ft_null_
 
Eigen::MatrixXd ft_raw_
 
geometry_msgs::WrenchStamped ft_raw_msg_
 
ros::Publisher ft_raw_pub_
 
std::string ft_raw_publish_name_
 
double ft_scale_factor_
 
boost::mutex ft_scale_param_mutex_
 
Eigen::MatrixXd ft_scaled_
 
geometry_msgs::WrenchStamped ft_scaled_msg_
 
ros::Publisher ft_scaled_pub_
 
std::string ft_scaled_publish_name_
 
Eigen::MatrixXd ft_unload_volatge_
 
bool is_ft_raw_published_
 
bool is_ft_scaled_published_
 

Detailed Description

Definition at line 32 of file ati_force_torque_sensor_twe.h.

Constructor & Destructor Documentation

ATIForceTorqueSensorTWE::ATIForceTorqueSensorTWE ( )

Definition at line 21 of file ati_force_torque_sensor_twe.cpp.

ATIForceTorqueSensorTWE::~ATIForceTorqueSensorTWE ( )

Definition at line 48 of file ati_force_torque_sensor_twe.cpp.

Member Function Documentation

Eigen::MatrixXd ATIForceTorqueSensorTWE::getCurrentForceTorqueRaw ( )

Definition at line 177 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::getCurrentForceTorqueRaw ( double *  force_x_N,
double *  force_y_N,
double *  force_z_N,
double *  torque_x_Nm,
double *  torque_y_Nm,
double *  torque_z_Nm 
)

Definition at line 187 of file ati_force_torque_sensor_twe.cpp.

Eigen::MatrixXd ATIForceTorqueSensorTWE::getCurrentForceTorqueScaled ( )

Definition at line 182 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::getCurrentForceTorqueScaled ( double *  force_x_N,
double *  force_y_N,
double *  force_z_N,
double *  torque_x_Nm,
double *  torque_y_Nm,
double *  torque_z_Nm 
)

Definition at line 198 of file ati_force_torque_sensor_twe.cpp.

bool ATIForceTorqueSensorTWE::initialize ( const std::string &  ft_data_path,
const std::string &  ft_data_key,
const std::string &  ft_frame_id,
const std::string &  ft_raw_publish_name,
const std::string &  ft_scaled_publish_name 
)

Definition at line 54 of file ati_force_torque_sensor_twe.cpp.

bool ATIForceTorqueSensorTWE::parseFTData ( const std::string &  ft_data_path,
const std::string &  ft_data_key 
)
private

Definition at line 105 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::setCurrentVoltageOutput ( double  voltage0,
double  voltage1,
double  voltage2,
double  voltage3,
double  voltage4,
double  voltage5 
)

Definition at line 132 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::setCurrentVoltageOutput ( Eigen::MatrixXd  voltage)

Definition at line 166 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::setCurrentVoltageOutputPublish ( double  voltage0,
double  voltage1,
double  voltage2,
double  voltage3,
double  voltage4,
double  voltage5 
)

Definition at line 209 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::setCurrentVoltageOutputPublish ( Eigen::MatrixXd  voltage)

Definition at line 221 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::setNullForceTorque ( Eigen::MatrixXd  _ft_null)

Definition at line 87 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::setScaleFactror ( double  ft_scale_factor)

Definition at line 80 of file ati_force_torque_sensor_twe.cpp.

void ATIForceTorqueSensorTWE::setScaleParam ( double  ft_scale_factor,
Eigen::MatrixXd  ft_null 
)

Definition at line 99 of file ati_force_torque_sensor_twe.cpp.

Member Data Documentation

Eigen::MatrixXd thormang3::ATIForceTorqueSensorTWE::ft_coeff_mat_
private

Definition at line 66 of file ati_force_torque_sensor_twe.h.

Eigen::MatrixXd thormang3::ATIForceTorqueSensorTWE::ft_current_volatge_
private

Definition at line 68 of file ati_force_torque_sensor_twe.h.

std::string thormang3::ATIForceTorqueSensorTWE::ft_frame_id_
private

Definition at line 78 of file ati_force_torque_sensor_twe.h.

Eigen::MatrixXd thormang3::ATIForceTorqueSensorTWE::ft_null_
private

Definition at line 69 of file ati_force_torque_sensor_twe.h.

Eigen::MatrixXd thormang3::ATIForceTorqueSensorTWE::ft_raw_
private

Definition at line 70 of file ati_force_torque_sensor_twe.h.

geometry_msgs::WrenchStamped thormang3::ATIForceTorqueSensorTWE::ft_raw_msg_
private

Definition at line 89 of file ati_force_torque_sensor_twe.h.

ros::Publisher thormang3::ATIForceTorqueSensorTWE::ft_raw_pub_
private

Definition at line 86 of file ati_force_torque_sensor_twe.h.

std::string thormang3::ATIForceTorqueSensorTWE::ft_raw_publish_name_
private

Definition at line 79 of file ati_force_torque_sensor_twe.h.

double thormang3::ATIForceTorqueSensorTWE::ft_scale_factor_
private

Definition at line 76 of file ati_force_torque_sensor_twe.h.

boost::mutex thormang3::ATIForceTorqueSensorTWE::ft_scale_param_mutex_
private

Definition at line 73 of file ati_force_torque_sensor_twe.h.

Eigen::MatrixXd thormang3::ATIForceTorqueSensorTWE::ft_scaled_
private

Definition at line 71 of file ati_force_torque_sensor_twe.h.

geometry_msgs::WrenchStamped thormang3::ATIForceTorqueSensorTWE::ft_scaled_msg_
private

Definition at line 90 of file ati_force_torque_sensor_twe.h.

ros::Publisher thormang3::ATIForceTorqueSensorTWE::ft_scaled_pub_
private

Definition at line 87 of file ati_force_torque_sensor_twe.h.

std::string thormang3::ATIForceTorqueSensorTWE::ft_scaled_publish_name_
private

Definition at line 80 of file ati_force_torque_sensor_twe.h.

Eigen::MatrixXd thormang3::ATIForceTorqueSensorTWE::ft_unload_volatge_
private

Definition at line 67 of file ati_force_torque_sensor_twe.h.

bool thormang3::ATIForceTorqueSensorTWE::is_ft_raw_published_
private

Definition at line 82 of file ati_force_torque_sensor_twe.h.

bool thormang3::ATIForceTorqueSensorTWE::is_ft_scaled_published_
private

Definition at line 83 of file ati_force_torque_sensor_twe.h.


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


ati_ft_sensor
Author(s): Kayman , Jay Song
autogenerated on Mon Jun 10 2019 15:37:37