#include <action_module.h>

Public Member Functions | |
| ActionModule () | |
| void | actionPlayProcess (std::map< std::string, robotis_framework::Dynamixel * > dxls) |
| void | brake () |
| bool | createFile (std::string file_name) |
| void | enableAllJoints () |
| void | initialize (const int control_cycle_msec, robotis_framework::Robot *robot) |
| bool | isRunning () |
| bool | isRunning (int *playing_page_num, int *playing_step_num) |
| bool | loadFile (std::string file_name) |
| bool | loadPage (int page_number, action_file_define::Page *page) |
| void | onModuleDisable () |
| void | onModuleEnable () |
| void | process (std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors) |
| void | resetPage (action_file_define::Page *page) |
| bool | savePage (int page_number, action_file_define::Page *page) |
| bool | start (int page_number) |
| bool | start (std::string page_name) |
| bool | start (int page_number, action_file_define::Page *page) |
| void | stop () |
| virtual | ~ActionModule () |
Public Member Functions inherited from robotis_framework::MotionModule | |
| ControlMode | getControlMode () |
| bool | getModuleEnable () |
| std::string | getModuleName () |
| void | setModuleEnable (bool enable) |
| virtual | ~MotionModule () |
Private Member Functions | |
| std::string | convertIntToString (int n) |
| int | convertRadTow4095 (double rad) |
| double | convertw4095ToRad (int w4095) |
| bool | isRunningServiceCallback (thormang3_action_module_msgs::IsRunning::Request &req, thormang3_action_module_msgs::IsRunning::Response &res) |
| void | pageNumberCallback (const std_msgs::Int32::ConstPtr &msg) |
| void | publishDoneMsg (std::string msg) |
| void | publishStatusMsg (unsigned int type, std::string msg) |
| void | queueThread () |
| void | setChecksum (action_file_define::Page *page) |
| void | startActionCallback (const thormang3_action_module_msgs::StartAction::ConstPtr &msg) |
| bool | verifyChecksum (action_file_define::Page *page) |
Private Attributes | |
| FILE * | action_file_ |
| std::map< std::string, bool > | action_joints_enable_ |
| bool | action_module_enabled_ |
| std::map< std::string, robotis_framework::DynamixelState * > | action_result_ |
| int | control_cycle_msec_ |
| action_file_define::Step | current_step_ |
| ros::Publisher | done_msg_pub_ |
| bool | first_driving_start_ |
| std::map< int, std::string > | joint_id_to_name_ |
| std::map< std::string, int > | joint_name_to_id_ |
| const int | MAIN_SECTION |
| action_file_define::Page | next_play_page_ |
| const int | NONE_ZERO_FINISH |
| int | page_step_count_ |
| const int | PAUSE_SECTION |
| action_file_define::Page | play_page_ |
| int | play_page_idx_ |
| bool | playing_ |
| bool | playing_finished_ |
| const int | POST_SECTION |
| const int | PRE_SECTION |
| bool | present_running_ |
| bool | previous_running_ |
| boost::thread | queue_thread_ |
| ros::Publisher | status_msg_pub_ |
| bool | stop_playing_ |
| const int | ZERO_FINISH |
Additional Inherited Members | |
Static Public Member Functions inherited from robotis_framework::Singleton< ActionModule > | |
| 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< ActionModule > | |
| 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 49 of file action_module.h.
| ActionModule::ActionModule | ( | ) |
Definition at line 37 of file action_module.cpp.
|
virtual |
Definition at line 75 of file action_module.cpp.
| void ActionModule::actionPlayProcess | ( | std::map< std::string, robotis_framework::Dynamixel * > | dxls | ) |
Definition at line 575 of file action_module.cpp.
| void ActionModule::brake | ( | ) |
Definition at line 484 of file action_module.cpp.
|
private |
Definition at line 31 of file action_module.cpp.
|
private |
Definition at line 317 of file action_module.cpp.
|
private |
Definition at line 322 of file action_module.cpp.
| bool ActionModule::createFile | ( | std::string | file_name | ) |
Definition at line 388 of file action_module.cpp.
| void ActionModule::enableAllJoints | ( | ) |
Definition at line 565 of file action_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 84 of file action_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 312 of file action_module.cpp.
| bool ActionModule::isRunning | ( | int * | playing_page_num, |
| int * | playing_step_num | ||
| ) |
Definition at line 489 of file action_module.cpp.
|
private |
Definition at line 136 of file action_module.cpp.
| bool ActionModule::loadFile | ( | std::string | file_name | ) |
Definition at line 360 of file action_module.cpp.
| bool ActionModule::loadPage | ( | int | page_number, |
| action_file_define::Page * | page | ||
| ) |
Definition at line 500 of file action_module.cpp.
|
virtual |
Reimplemented from robotis_framework::MotionModule.
Definition at line 301 of file action_module.cpp.
|
virtual |
Reimplemented from robotis_framework::MotionModule.
Definition at line 296 of file action_module.cpp.
|
private |
Definition at line 143 of file action_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 241 of file action_module.cpp.
|
private |
Definition at line 1042 of file action_module.cpp.
|
private |
Definition at line 1031 of file action_module.cpp.
|
private |
Definition at line 113 of file action_module.cpp.
| void ActionModule::resetPage | ( | action_file_define::Page * | page | ) |
Definition at line 535 of file action_module.cpp.
| bool ActionModule::savePage | ( | int | page_number, |
| action_file_define::Page * | page | ||
| ) |
Definition at line 519 of file action_module.cpp.
|
private |
Definition at line 344 of file action_module.cpp.
| bool ActionModule::start | ( | int | page_number | ) |
Definition at line 413 of file action_module.cpp.
| bool ActionModule::start | ( | std::string | page_name | ) |
Definition at line 427 of file action_module.cpp.
| bool ActionModule::start | ( | int | page_number, |
| action_file_define::Page * | page | ||
| ) |
Definition at line 449 of file action_module.cpp.
|
private |
Definition at line 183 of file action_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 307 of file action_module.cpp.
|
private |
Definition at line 327 of file action_module.cpp.
|
private |
Definition at line 109 of file action_module.h.
|
private |
Definition at line 99 of file action_module.h.
|
private |
Definition at line 122 of file action_module.h.
|
private |
Definition at line 100 of file action_module.h.
|
private |
Definition at line 101 of file action_module.h.
|
private |
Definition at line 112 of file action_module.h.
|
private |
Definition at line 105 of file action_module.h.
|
private |
Definition at line 115 of file action_module.h.
|
private |
Definition at line 108 of file action_module.h.
|
private |
Definition at line 107 of file action_module.h.
|
private |
Definition at line 127 of file action_module.h.
|
private |
Definition at line 111 of file action_module.h.
|
private |
Definition at line 131 of file action_module.h.
|
private |
Definition at line 116 of file action_module.h.
|
private |
Definition at line 129 of file action_module.h.
|
private |
Definition at line 110 of file action_module.h.
|
private |
Definition at line 114 of file action_module.h.
|
private |
Definition at line 118 of file action_module.h.
|
private |
Definition at line 120 of file action_module.h.
|
private |
Definition at line 128 of file action_module.h.
|
private |
Definition at line 126 of file action_module.h.
|
private |
Definition at line 124 of file action_module.h.
|
private |
Definition at line 123 of file action_module.h.
|
private |
Definition at line 102 of file action_module.h.
|
private |
Definition at line 104 of file action_module.h.
|
private |
Definition at line 119 of file action_module.h.
|
private |
Definition at line 130 of file action_module.h.