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

#include <gripper_module.h>

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

Public Member Functions

 GripperModule ()
 
void initialize (const int control_cycle_msec, robotis_framework::Robot *robot)
 
bool isRunning ()
 
void process (std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
 
void publishStatusMsg (unsigned int type, std::string msg)
 
void setModeMsgCallback (const std_msgs::String::ConstPtr &msg)
 
void stop ()
 
virtual ~GripperModule ()
 
- Public Member Functions inherited from robotis_framework::MotionModule
ControlMode getControlMode ()
 
bool getModuleEnable ()
 
std::string getModuleName ()
 
virtual void onModuleDisable ()
 
virtual void onModuleEnable ()
 
void setModuleEnable (bool enable)
 
virtual ~MotionModule ()
 

Private Member Functions

void queueThread ()
 
void setEndTrajectory ()
 
void setJointPoseMsgCallback (const sensor_msgs::JointState::ConstPtr &msg)
 
void setTorqueLimit ()
 
void traGeneProcJointSpace ()
 

Private Attributes

int all_time_steps_
 
int cnt_
 
double control_cycle_sec_
 
sensor_msgs::JointState goal_joint_pose_msg_
 
Eigen::VectorXd goal_joint_position_
 
Eigen::MatrixXd goal_joint_tra_
 
ros::Publisher goal_torque_limit_pub_
 
bool is_moving_
 
std::map< std::string, int > joint_name_to_id_
 
double mov_time_
 
std_msgs::String movement_done_msg_
 
ros::Publisher movement_done_pub_
 
Eigen::VectorXd present_joint_position_
 
Eigen::VectorXd present_joint_velocity_
 
boost::thread queue_thread_
 
ros::Publisher set_ctrl_module_pub_
 
ros::Publisher status_msg_pub_
 
boost::thread * tra_gene_tread_
 

Additional Inherited Members

- Static Public Member Functions inherited from robotis_framework::Singleton< GripperModule >
static void destroyInstance ()
 
static T * getInstance ()
 
- Public Attributes inherited from robotis_framework::MotionModule
std::map< std::string, DynamixelState * > result_
 
- Protected Member Functions inherited from robotis_framework::Singleton< GripperModule >
Singletonoperator= (Singleton const &)
 
 Singleton (Singleton const &)
 
 Singleton ()
 
- Protected Attributes inherited from robotis_framework::MotionModule
ControlMode control_mode_
 
bool enable_
 
std::string module_name_
 

Detailed Description

Definition at line 46 of file gripper_module.h.

Constructor & Destructor Documentation

GripperModule::GripperModule ( )

Definition at line 22 of file gripper_module.cpp.

GripperModule::~GripperModule ( )
virtual

Definition at line 44 of file gripper_module.cpp.

Member Function Documentation

void GripperModule::initialize ( const int  control_cycle_msec,
robotis_framework::Robot robot 
)
virtual

Implements robotis_framework::MotionModule.

Definition at line 49 of file gripper_module.cpp.

bool GripperModule::isRunning ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 250 of file gripper_module.cpp.

void GripperModule::process ( std::map< std::string, robotis_framework::Dynamixel * >  dxls,
std::map< std::string, double >  sensors 
)
virtual

Implements robotis_framework::MotionModule.

Definition at line 192 of file gripper_module.cpp.

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

Definition at line 255 of file gripper_module.cpp.

void GripperModule::queueThread ( )
private

Definition at line 55 of file gripper_module.cpp.

void GripperModule::setEndTrajectory ( )
private

Definition at line 174 of file gripper_module.cpp.

void GripperModule::setJointPoseMsgCallback ( const sensor_msgs::JointState::ConstPtr &  msg)
private

Definition at line 90 of file gripper_module.cpp.

void GripperModule::setModeMsgCallback ( const std_msgs::String::ConstPtr &  msg)

Definition at line 81 of file gripper_module.cpp.

void GripperModule::setTorqueLimit ( )
private

Definition at line 157 of file gripper_module.cpp.

void GripperModule::stop ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 243 of file gripper_module.cpp.

void GripperModule::traGeneProcJointSpace ( )
private

Definition at line 112 of file gripper_module.cpp.

Member Data Documentation

int thormang3::GripperModule::all_time_steps_
private

Definition at line 76 of file gripper_module.h.

int thormang3::GripperModule::cnt_
private

Definition at line 77 of file gripper_module.h.

double thormang3::GripperModule::control_cycle_sec_
private

Definition at line 51 of file gripper_module.h.

sensor_msgs::JointState thormang3::GripperModule::goal_joint_pose_msg_
private

Definition at line 70 of file gripper_module.h.

Eigen::VectorXd thormang3::GripperModule::goal_joint_position_
private

Definition at line 68 of file gripper_module.h.

Eigen::MatrixXd thormang3::GripperModule::goal_joint_tra_
private

Definition at line 79 of file gripper_module.h.

ros::Publisher thormang3::GripperModule::goal_torque_limit_pub_
private

Definition at line 58 of file gripper_module.h.

bool thormang3::GripperModule::is_moving_
private

Definition at line 64 of file gripper_module.h.

std::map<std::string, int> thormang3::GripperModule::joint_name_to_id_
private

Definition at line 61 of file gripper_module.h.

double thormang3::GripperModule::mov_time_
private

Definition at line 75 of file gripper_module.h.

std_msgs::String thormang3::GripperModule::movement_done_msg_
private

Definition at line 72 of file gripper_module.h.

ros::Publisher thormang3::GripperModule::movement_done_pub_
private

Definition at line 59 of file gripper_module.h.

Eigen::VectorXd thormang3::GripperModule::present_joint_position_
private

Definition at line 66 of file gripper_module.h.

Eigen::VectorXd thormang3::GripperModule::present_joint_velocity_
private

Definition at line 67 of file gripper_module.h.

boost::thread thormang3::GripperModule::queue_thread_
private

Definition at line 52 of file gripper_module.h.

ros::Publisher thormang3::GripperModule::set_ctrl_module_pub_
private

Definition at line 57 of file gripper_module.h.

ros::Publisher thormang3::GripperModule::status_msg_pub_
private

Definition at line 56 of file gripper_module.h.

boost::thread* thormang3::GripperModule::tra_gene_tread_
private

Definition at line 53 of file gripper_module.h.


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


thormang3_gripper_module
Author(s): SCH
autogenerated on Mon Jun 10 2019 15:37:46