#include <manipulation_module.h>

Public Member Functions | |
| bool | getJointPoseCallback (thormang3_manipulation_module_msgs::GetJointPose::Request &req, thormang3_manipulation_module_msgs::GetJointPose::Response &res) |
| bool | getKinematicsPoseCallback (thormang3_manipulation_module_msgs::GetKinematicsPose::Request &req, thormang3_manipulation_module_msgs::GetKinematicsPose::Response &res) |
| void | initialize (const int control_cycle_msec, robotis_framework::Robot *robot) |
| void | initPoseMsgCallback (const std_msgs::String::ConstPtr &msg) |
| void | initPoseTrajGenerateProc () |
| bool | isRunning () |
| void | jointPoseMsgCallback (const thormang3_manipulation_module_msgs::JointPose::ConstPtr &msg) |
| void | jointTrajGenerateProc () |
| void | kinematicsPoseMsgCallback (const thormang3_manipulation_module_msgs::KinematicsPose::ConstPtr &msg) |
| ManipulationModule () | |
| 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 | stop () |
| void | taskTrajGenerateProc () |
| virtual | ~ManipulationModule () |
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 () |
Public Attributes | |
| KinematicsDynamics * | robotis_ |
Public Attributes inherited from robotis_framework::MotionModule | |
| std::map< std::string, DynamixelState * > | result_ |
Private Member Functions | |
| void | parseData (const std::string &path) |
| void | parseIniPoseData (const std::string &path) |
| void | queueThread () |
| void | setInverseKinematics (int cnt, Eigen::MatrixXd start_rotation) |
Private Attributes | |
| int | all_time_steps_ |
| bool | arm_angle_display_ |
| int | cnt_ |
| double | control_cycle_sec_ |
| thormang3_manipulation_module_msgs::JointPose | goal_joint_pose_msg_ |
| Eigen::VectorXd | goal_joint_position_ |
| Eigen::MatrixXd | goal_joint_tra_ |
| thormang3_manipulation_module_msgs::KinematicsPose | goal_kinematics_pose_msg_ |
| Eigen::MatrixXd | goal_task_tra_ |
| int | ik_id_end_ |
| int | ik_id_start_ |
| bool | ik_solving_ |
| Eigen::MatrixXd | ik_start_rotation_ |
| Eigen::MatrixXd | ik_target_position_ |
| Eigen::MatrixXd | ik_target_rotation_ |
| Eigen::MatrixXd | ik_weight_ |
| Eigen::VectorXd | init_joint_position_ |
| 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_ |
| boost::thread | queue_thread_ |
| ros::Publisher | status_msg_pub_ |
| boost::thread * | traj_generate_tread_ |
Additional Inherited Members | |
Static Public Member Functions inherited from robotis_framework::Singleton< ManipulationModule > | |
| static void | destroyInstance () |
| static T * | getInstance () |
Protected Member Functions inherited from robotis_framework::Singleton< ManipulationModule > | |
| 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 56 of file manipulation_module.h.
| ManipulationModule::ManipulationModule | ( | ) |
Definition at line 28 of file manipulation_module.cpp.
|
virtual |
Definition at line 91 of file manipulation_module.cpp.
| bool ManipulationModule::getJointPoseCallback | ( | thormang3_manipulation_module_msgs::GetJointPose::Request & | req, |
| thormang3_manipulation_module_msgs::GetJointPose::Response & | res | ||
| ) |
Definition at line 220 of file manipulation_module.cpp.
| bool ManipulationModule::getKinematicsPoseCallback | ( | thormang3_manipulation_module_msgs::GetKinematicsPose::Request & | req, |
| thormang3_manipulation_module_msgs::GetKinematicsPose::Response & | res | ||
| ) |
Definition at line 238 of file manipulation_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 96 of file manipulation_module.cpp.
| void ManipulationModule::initPoseMsgCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 193 of file manipulation_module.cpp.
| void ManipulationModule::initPoseTrajGenerateProc | ( | ) |
Definition at line 332 of file manipulation_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 623 of file manipulation_module.cpp.
| void ManipulationModule::jointPoseMsgCallback | ( | const thormang3_manipulation_module_msgs::JointPose::ConstPtr & | msg | ) |
Definition at line 314 of file manipulation_module.cpp.
| void ManipulationModule::jointTrajGenerateProc | ( | ) |
Definition at line 353 of file manipulation_module.cpp.
| void ManipulationModule::kinematicsPoseMsgCallback | ( | const thormang3_manipulation_module_msgs::KinematicsPose::ConstPtr & | msg | ) |
Definition at line 271 of file manipulation_module.cpp.
|
private |
Definition at line 113 of file manipulation_module.cpp.
|
private |
Definition at line 136 of file manipulation_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 479 of file manipulation_module.cpp.
| void ManipulationModule::publishStatusMsg | ( | unsigned int | type, |
| std::string | msg | ||
| ) |
Definition at line 628 of file manipulation_module.cpp.
|
private |
Definition at line 167 of file manipulation_module.cpp.
|
private |
Definition at line 460 of file manipulation_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 614 of file manipulation_module.cpp.
| void ManipulationModule::taskTrajGenerateProc | ( | ) |
Definition at line 405 of file manipulation_module.cpp.
|
private |
Definition at line 115 of file manipulation_module.h.
|
private |
Definition at line 95 of file manipulation_module.h.
|
private |
Definition at line 114 of file manipulation_module.h.
|
private |
Definition at line 97 of file manipulation_module.h.
|
private |
Definition at line 121 of file manipulation_module.h.
|
private |
Definition at line 108 of file manipulation_module.h.
|
private |
Definition at line 117 of file manipulation_module.h.
|
private |
Definition at line 122 of file manipulation_module.h.
|
private |
Definition at line 118 of file manipulation_module.h.
|
private |
Definition at line 127 of file manipulation_module.h.
|
private |
Definition at line 126 of file manipulation_module.h.
|
private |
Definition at line 125 of file manipulation_module.h.
|
private |
Definition at line 130 of file manipulation_module.h.
|
private |
Definition at line 129 of file manipulation_module.h.
|
private |
Definition at line 131 of file manipulation_module.h.
|
private |
Definition at line 132 of file manipulation_module.h.
|
private |
Definition at line 109 of file manipulation_module.h.
|
private |
Definition at line 112 of file manipulation_module.h.
|
private |
Definition at line 136 of file manipulation_module.h.
|
private |
Definition at line 113 of file manipulation_module.h.
|
private |
Definition at line 101 of file manipulation_module.h.
|
private |
Definition at line 104 of file manipulation_module.h.
|
private |
Definition at line 107 of file manipulation_module.h.
|
private |
Definition at line 98 of file manipulation_module.h.
| KinematicsDynamics* thormang3::ManipulationModule::robotis_ |
Definition at line 87 of file manipulation_module.h.
|
private |
Definition at line 103 of file manipulation_module.h.
|
private |
Definition at line 99 of file manipulation_module.h.