#include <base_module.h>

Public Member Functions | |
| BaseModule () | |
| void | initialize (const int control_cycle_msec, robotis_framework::Robot *robot) |
| void | initPoseMsgCallback (const std_msgs::String::ConstPtr &msg) |
| void | initPoseTrajGenerateProc () |
| bool | isRunning () |
| void | onModuleDisable () |
| void | onModuleEnable () |
| void | poseGenerateProc (Eigen::MatrixXd joint_angle_pose) |
| void | poseGenerateProc (std::map< std::string, double > &joint_angle_pose) |
| void | process (std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors) |
| void | stop () |
| virtual | ~BaseModule () |
Public Member Functions inherited from robotis_framework::MotionModule | |
| ControlMode | getControlMode () |
| bool | getModuleEnable () |
| std::string | getModuleName () |
| void | setModuleEnable (bool enable) |
| virtual | ~MotionModule () |
Public Attributes | |
| BaseModuleState * | base_module_state_ |
| BaseJointState * | joint_state_ |
Public Attributes inherited from robotis_framework::MotionModule | |
| std::map< std::string, DynamixelState * > | result_ |
Private Member Functions | |
| void | callServiceSettingModule (const std::string &module_name) |
| void | parseInitPoseData (const std::string &path) |
| void | publishStatusMsg (unsigned int type, std::string msg) |
| void | queueThread () |
| void | setCtrlModule (std::string module) |
Private Attributes | |
| int | control_cycle_msec_ |
| bool | has_goal_joints_ |
| bool | ini_pose_only_ |
| std::map< std::string, int > | joint_name_to_id_ |
| boost::thread | queue_thread_ |
| ros::Publisher | set_ctrl_module_pub_ |
| ros::ServiceClient | set_module_client_ |
| ros::Publisher | status_msg_pub_ |
| boost::thread | tra_gene_tread_ |
Additional Inherited Members | |
Static Public Member Functions inherited from robotis_framework::Singleton< BaseModule > | |
| static void | destroyInstance () |
| static T * | getInstance () |
Protected Member Functions inherited from robotis_framework::Singleton< BaseModule > | |
| 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 69 of file base_module.h.
| robotis_op::BaseModule::BaseModule | ( | ) |
Definition at line 25 of file base_module.cpp.
|
virtual |
Definition at line 38 of file base_module.cpp.
|
private |
Definition at line 398 of file base_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 43 of file base_module.cpp.
| void robotis_op::BaseModule::initPoseMsgCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 156 of file base_module.cpp.
| void robotis_op::BaseModule::initPoseTrajGenerateProc | ( | ) |
Definition at line 183 of file base_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 301 of file base_module.cpp.
|
virtual |
Reimplemented from robotis_framework::MotionModule.
Definition at line 385 of file base_module.cpp.
|
virtual |
Reimplemented from robotis_framework::MotionModule.
Definition at line 380 of file base_module.cpp.
|
private |
Definition at line 67 of file base_module.cpp.
| void robotis_op::BaseModule::poseGenerateProc | ( | Eigen::MatrixXd | joint_angle_pose | ) |
Definition at line 218 of file base_module.cpp.
| void robotis_op::BaseModule::poseGenerateProc | ( | std::map< std::string, double > & | joint_angle_pose | ) |
Definition at line 252 of file base_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 306 of file base_module.cpp.
|
private |
Definition at line 412 of file base_module.cpp.
|
private |
Definition at line 139 of file base_module.cpp.
|
private |
Definition at line 390 of file base_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 375 of file base_module.cpp.
| BaseModuleState* robotis_op::BaseModule::base_module_state_ |
Definition at line 95 of file base_module.h.
|
private |
Definition at line 105 of file base_module.h.
|
private |
Definition at line 116 of file base_module.h.
|
private |
Definition at line 117 of file base_module.h.
|
private |
Definition at line 114 of file base_module.h.
| BaseJointState* robotis_op::BaseModule::joint_state_ |
Definition at line 96 of file base_module.h.
|
private |
Definition at line 106 of file base_module.h.
|
private |
Definition at line 110 of file base_module.h.
|
private |
Definition at line 112 of file base_module.h.
|
private |
Definition at line 109 of file base_module.h.
|
private |
Definition at line 107 of file base_module.h.