#include <gripper_module.h>

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 > | |
| Singleton & | operator= (Singleton const &) |
| Singleton (Singleton const &) | |
| Singleton () | |
Protected Attributes inherited from robotis_framework::MotionModule | |
| ControlMode | control_mode_ |
| bool | enable_ |
| std::string | module_name_ |
Definition at line 46 of file gripper_module.h.
| GripperModule::GripperModule | ( | ) |
Definition at line 22 of file gripper_module.cpp.
|
virtual |
Definition at line 44 of file gripper_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 49 of file gripper_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 250 of file gripper_module.cpp.
|
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.
|
private |
Definition at line 55 of file gripper_module.cpp.
|
private |
Definition at line 174 of file gripper_module.cpp.
|
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.
|
private |
Definition at line 157 of file gripper_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 243 of file gripper_module.cpp.
|
private |
Definition at line 112 of file gripper_module.cpp.
|
private |
Definition at line 76 of file gripper_module.h.
|
private |
Definition at line 77 of file gripper_module.h.
|
private |
Definition at line 51 of file gripper_module.h.
|
private |
Definition at line 70 of file gripper_module.h.
|
private |
Definition at line 68 of file gripper_module.h.
|
private |
Definition at line 79 of file gripper_module.h.
|
private |
Definition at line 58 of file gripper_module.h.
|
private |
Definition at line 64 of file gripper_module.h.
|
private |
Definition at line 61 of file gripper_module.h.
|
private |
Definition at line 75 of file gripper_module.h.
|
private |
Definition at line 72 of file gripper_module.h.
|
private |
Definition at line 59 of file gripper_module.h.
|
private |
Definition at line 66 of file gripper_module.h.
|
private |
Definition at line 67 of file gripper_module.h.
|
private |
Definition at line 52 of file gripper_module.h.
|
private |
Definition at line 57 of file gripper_module.h.
|
private |
Definition at line 56 of file gripper_module.h.
|
private |
Definition at line 53 of file gripper_module.h.