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

#include <feet_force_torque_sensor_module.h>

Inheritance diagram for thormang3::FeetForceTorqueSensor:
Inheritance graph
[legend]

Public Member Functions

 FeetForceTorqueSensor ()
 
void initialize (const int control_cycle_msec, robotis_framework::Robot *robot)
 
void process (std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, robotis_framework::Sensor * > sensors)
 
 ~FeetForceTorqueSensor ()
 
- Public Member Functions inherited from robotis_framework::SensorModule
std::string getModuleName ()
 
virtual ~SensorModule ()
 

Public Attributes

double l_foot_fx_raw_N_
 
double l_foot_fx_scaled_N_
 
double l_foot_fy_raw_N_
 
double l_foot_fy_scaled_N_
 
double l_foot_fz_raw_N_
 
double l_foot_fz_scaled_N_
 
double l_foot_tx_raw_Nm_
 
double l_foot_tx_scaled_Nm_
 
double l_foot_ty_raw_Nm_
 
double l_foot_ty_scaled_Nm_
 
double l_foot_tz_raw_Nm_
 
double l_foot_tz_scaled_Nm_
 
double r_foot_fx_raw_N_
 
double r_foot_fx_scaled_N_
 
double r_foot_fy_raw_N_
 
double r_foot_fy_scaled_N_
 
double r_foot_fz_raw_N_
 
double r_foot_fz_scaled_N_
 
double r_foot_tx_raw_Nm_
 
double r_foot_tx_scaled_Nm_
 
double r_foot_ty_raw_Nm_
 
double r_foot_ty_scaled_Nm_
 
double r_foot_tz_raw_Nm_
 
double r_foot_tz_scaled_Nm_
 
- Public Attributes inherited from robotis_framework::SensorModule
std::map< std::string, double > result_
 

Private Member Functions

void ftSensorCalibrationCommandCallback (const std_msgs::String::ConstPtr &msg)
 
void initializeFeetForceTorqueSensor ()
 
void publishBothFTData (int type, Eigen::MatrixXd &ft_right, Eigen::MatrixXd &ft_left)
 
void publishStatusMsg (unsigned int type, std::string msg)
 
void queueThread ()
 
void saveFTCalibrationData (const std::string &path)
 

Private Attributes

int control_cycle_msec_
 
bool exist_l_leg_an_p_
 
bool exist_l_leg_an_r_
 
bool exist_r_leg_an_p_
 
bool exist_r_leg_an_r_
 
const int FT_AIR
 
const int FT_CALC
 
int ft_command_
 
int ft_get_count_
 
const int FT_GND
 
const int FT_NONE
 
int ft_period_
 
bool has_ft_air_
 
bool has_ft_gnd_
 
Eigen::MatrixXd l_foot_ft_air_
 
double l_foot_ft_current_voltage_ [6]
 
Eigen::MatrixXd l_foot_ft_gnd_
 
double l_foot_ft_scale_factor_
 
ATIForceTorqueSensorTWE l_foot_ft_sensor_
 
boost::mutex publish_mutex_
 
boost::thread queue_thread_
 
Eigen::MatrixXd r_foot_ft_air_
 
double r_foot_ft_current_voltage_ [6]
 
Eigen::MatrixXd r_foot_ft_gnd_
 
double r_foot_ft_scale_factor_
 
ATIForceTorqueSensorTWE r_foot_ft_sensor_
 
ros::Publisher thormang3_foot_ft_both_ft_pub_
 
ros::Publisher thormang3_foot_ft_status_pub_
 
KinematicsDynamicsthormang3_kd_
 
double total_mass_
 

Additional Inherited Members

- Static Public Member Functions inherited from robotis_framework::Singleton< FeetForceTorqueSensor >
static void destroyInstance ()
 
static T * getInstance ()
 
- Protected Member Functions inherited from robotis_framework::Singleton< FeetForceTorqueSensor >
Singletonoperator= (Singleton const &)
 
 Singleton (Singleton const &)
 
 Singleton ()
 
- Protected Attributes inherited from robotis_framework::SensorModule
std::string module_name_
 

Detailed Description

Definition at line 46 of file feet_force_torque_sensor_module.h.

Constructor & Destructor Documentation

FeetForceTorqueSensor::FeetForceTorqueSensor ( )

Definition at line 33 of file feet_force_torque_sensor_module.cpp.

FeetForceTorqueSensor::~FeetForceTorqueSensor ( )

Definition at line 113 of file feet_force_torque_sensor_module.cpp.

Member Function Documentation

void FeetForceTorqueSensor::ftSensorCalibrationCommandCallback ( const std_msgs::String::ConstPtr &  msg)
private

Definition at line 211 of file feet_force_torque_sensor_module.cpp.

void FeetForceTorqueSensor::initialize ( const int  control_cycle_msec,
robotis_framework::Robot robot 
)
virtual
void FeetForceTorqueSensor::initializeFeetForceTorqueSensor ( )
private

Definition at line 131 of file feet_force_torque_sensor_module.cpp.

void FeetForceTorqueSensor::process ( std::map< std::string, robotis_framework::Dynamixel * >  dxls,
std::map< std::string, robotis_framework::Sensor * >  sensors 
)
virtual
void FeetForceTorqueSensor::publishBothFTData ( int  type,
Eigen::MatrixXd &  ft_right,
Eigen::MatrixXd &  ft_left 
)
private

Definition at line 283 of file feet_force_torque_sensor_module.cpp.

void FeetForceTorqueSensor::publishStatusMsg ( unsigned int  type,
std::string  msg 
)
private

Definition at line 272 of file feet_force_torque_sensor_module.cpp.

void FeetForceTorqueSensor::queueThread ( )
private

Definition at line 311 of file feet_force_torque_sensor_module.cpp.

void FeetForceTorqueSensor::saveFTCalibrationData ( const std::string &  path)
private

Definition at line 169 of file feet_force_torque_sensor_module.cpp.

Member Data Documentation

int thormang3::FeetForceTorqueSensor::control_cycle_msec_
private

Definition at line 77 of file feet_force_torque_sensor_module.h.

bool thormang3::FeetForceTorqueSensor::exist_l_leg_an_p_
private

Definition at line 86 of file feet_force_torque_sensor_module.h.

bool thormang3::FeetForceTorqueSensor::exist_l_leg_an_r_
private

Definition at line 86 of file feet_force_torque_sensor_module.h.

bool thormang3::FeetForceTorqueSensor::exist_r_leg_an_p_
private

Definition at line 85 of file feet_force_torque_sensor_module.h.

bool thormang3::FeetForceTorqueSensor::exist_r_leg_an_r_
private

Definition at line 85 of file feet_force_torque_sensor_module.h.

const int thormang3::FeetForceTorqueSensor::FT_AIR
private

Definition at line 108 of file feet_force_torque_sensor_module.h.

const int thormang3::FeetForceTorqueSensor::FT_CALC
private

Definition at line 110 of file feet_force_torque_sensor_module.h.

int thormang3::FeetForceTorqueSensor::ft_command_
private

Definition at line 103 of file feet_force_torque_sensor_module.h.

int thormang3::FeetForceTorqueSensor::ft_get_count_
private

Definition at line 105 of file feet_force_torque_sensor_module.h.

const int thormang3::FeetForceTorqueSensor::FT_GND
private

Definition at line 109 of file feet_force_torque_sensor_module.h.

const int thormang3::FeetForceTorqueSensor::FT_NONE
private

Definition at line 107 of file feet_force_torque_sensor_module.h.

int thormang3::FeetForceTorqueSensor::ft_period_
private

Definition at line 104 of file feet_force_torque_sensor_module.h.

bool thormang3::FeetForceTorqueSensor::has_ft_air_
private

Definition at line 101 of file feet_force_torque_sensor_module.h.

bool thormang3::FeetForceTorqueSensor::has_ft_gnd_
private

Definition at line 102 of file feet_force_torque_sensor_module.h.

Eigen::MatrixXd thormang3::FeetForceTorqueSensor::l_foot_ft_air_
private

Definition at line 91 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_ft_current_voltage_[6]
private

Definition at line 95 of file feet_force_torque_sensor_module.h.

Eigen::MatrixXd thormang3::FeetForceTorqueSensor::l_foot_ft_gnd_
private

Definition at line 92 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_ft_scale_factor_
private

Definition at line 99 of file feet_force_torque_sensor_module.h.

ATIForceTorqueSensorTWE thormang3::FeetForceTorqueSensor::l_foot_ft_sensor_
private

Definition at line 89 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_fx_raw_N_

Definition at line 55 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_fx_scaled_N_

Definition at line 60 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_fy_raw_N_

Definition at line 55 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_fy_scaled_N_

Definition at line 60 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_fz_raw_N_

Definition at line 55 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_fz_scaled_N_

Definition at line 60 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_tx_raw_Nm_

Definition at line 56 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_tx_scaled_Nm_

Definition at line 61 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_ty_raw_Nm_

Definition at line 56 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_ty_scaled_Nm_

Definition at line 61 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_tz_raw_Nm_

Definition at line 56 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::l_foot_tz_scaled_Nm_

Definition at line 61 of file feet_force_torque_sensor_module.h.

boost::mutex thormang3::FeetForceTorqueSensor::publish_mutex_
private

Definition at line 79 of file feet_force_torque_sensor_module.h.

boost::thread thormang3::FeetForceTorqueSensor::queue_thread_
private

Definition at line 78 of file feet_force_torque_sensor_module.h.

Eigen::MatrixXd thormang3::FeetForceTorqueSensor::r_foot_ft_air_
private

Definition at line 91 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_ft_current_voltage_[6]
private

Definition at line 94 of file feet_force_torque_sensor_module.h.

Eigen::MatrixXd thormang3::FeetForceTorqueSensor::r_foot_ft_gnd_
private

Definition at line 92 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_ft_scale_factor_
private

Definition at line 99 of file feet_force_torque_sensor_module.h.

ATIForceTorqueSensorTWE thormang3::FeetForceTorqueSensor::r_foot_ft_sensor_
private

Definition at line 88 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_fx_raw_N_

Definition at line 53 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_fx_scaled_N_

Definition at line 58 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_fy_raw_N_

Definition at line 53 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_fy_scaled_N_

Definition at line 58 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_fz_raw_N_

Definition at line 53 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_fz_scaled_N_

Definition at line 58 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_tx_raw_Nm_

Definition at line 54 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_tx_scaled_Nm_

Definition at line 59 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_ty_raw_Nm_

Definition at line 54 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_ty_scaled_Nm_

Definition at line 59 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_tz_raw_Nm_

Definition at line 54 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::r_foot_tz_scaled_Nm_

Definition at line 59 of file feet_force_torque_sensor_module.h.

ros::Publisher thormang3::FeetForceTorqueSensor::thormang3_foot_ft_both_ft_pub_
private

Definition at line 114 of file feet_force_torque_sensor_module.h.

ros::Publisher thormang3::FeetForceTorqueSensor::thormang3_foot_ft_status_pub_
private

Definition at line 113 of file feet_force_torque_sensor_module.h.

KinematicsDynamics* thormang3::FeetForceTorqueSensor::thormang3_kd_
private

Definition at line 82 of file feet_force_torque_sensor_module.h.

double thormang3::FeetForceTorqueSensor::total_mass_
private

Definition at line 98 of file feet_force_torque_sensor_module.h.


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


thormang3_feet_ft_module
Author(s): Zerom , SCH , Kayman , Jay Song
autogenerated on Mon Jun 10 2019 15:37:52