#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 (op3_action_module_msgs::IsRunning::Request &req, op3_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 op3_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_ |
const bool | DEBUG_PRINT |
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 41 of file action_module.h.
robotis_op::ActionModule::ActionModule | ( | ) |
Definition at line 33 of file action_module.cpp.
|
virtual |
Definition at line 71 of file action_module.cpp.
void robotis_op::ActionModule::actionPlayProcess | ( | std::map< std::string, robotis_framework::Dynamixel * > | dxls | ) |
Definition at line 588 of file action_module.cpp.
void robotis_op::ActionModule::brake | ( | ) |
Definition at line 498 of file action_module.cpp.
|
private |
Definition at line 26 of file action_module.cpp.
|
private |
Definition at line 323 of file action_module.cpp.
|
private |
Definition at line 328 of file action_module.cpp.
bool robotis_op::ActionModule::createFile | ( | std::string | file_name | ) |
Definition at line 394 of file action_module.cpp.
void robotis_op::ActionModule::enableAllJoints | ( | ) |
Definition at line 579 of file action_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 80 of file action_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 318 of file action_module.cpp.
bool robotis_op::ActionModule::isRunning | ( | int * | playing_page_num, |
int * | playing_step_num | ||
) |
Definition at line 503 of file action_module.cpp.
|
private |
Definition at line 137 of file action_module.cpp.
bool robotis_op::ActionModule::loadFile | ( | std::string | file_name | ) |
Definition at line 366 of file action_module.cpp.
bool robotis_op::ActionModule::loadPage | ( | int | page_number, |
action_file_define::Page * | page | ||
) |
Definition at line 514 of file action_module.cpp.
|
virtual |
Reimplemented from robotis_framework::MotionModule.
Definition at line 307 of file action_module.cpp.
|
virtual |
Reimplemented from robotis_framework::MotionModule.
Definition at line 302 of file action_module.cpp.
|
private |
Definition at line 144 of file action_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 243 of file action_module.cpp.
|
private |
Definition at line 1075 of file action_module.cpp.
|
private |
Definition at line 1064 of file action_module.cpp.
|
private |
Definition at line 111 of file action_module.cpp.
void robotis_op::ActionModule::resetPage | ( | action_file_define::Page * | page | ) |
Definition at line 549 of file action_module.cpp.
bool robotis_op::ActionModule::savePage | ( | int | page_number, |
action_file_define::Page * | page | ||
) |
Definition at line 533 of file action_module.cpp.
|
private |
Definition at line 350 of file action_module.cpp.
bool robotis_op::ActionModule::start | ( | int | page_number | ) |
Definition at line 419 of file action_module.cpp.
bool robotis_op::ActionModule::start | ( | std::string | page_name | ) |
Definition at line 437 of file action_module.cpp.
bool robotis_op::ActionModule::start | ( | int | page_number, |
action_file_define::Page * | page | ||
) |
Definition at line 463 of file action_module.cpp.
|
private |
Definition at line 184 of file action_module.cpp.
|
virtual |
Implements robotis_framework::MotionModule.
Definition at line 313 of file action_module.cpp.
|
private |
Definition at line 333 of file action_module.cpp.
|
private |
Definition at line 110 of file action_module.h.
|
private |
Definition at line 99 of file action_module.h.
|
private |
Definition at line 123 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 113 of file action_module.h.
|
private |
Definition at line 79 of file action_module.h.
|
private |
Definition at line 106 of file action_module.h.
|
private |
Definition at line 116 of file action_module.h.
|
private |
Definition at line 109 of file action_module.h.
|
private |
Definition at line 108 of file action_module.h.
|
private |
Definition at line 74 of file action_module.h.
|
private |
Definition at line 112 of file action_module.h.
|
private |
Definition at line 78 of file action_module.h.
|
private |
Definition at line 117 of file action_module.h.
|
private |
Definition at line 76 of file action_module.h.
|
private |
Definition at line 111 of file action_module.h.
|
private |
Definition at line 115 of file action_module.h.
|
private |
Definition at line 119 of file action_module.h.
|
private |
Definition at line 121 of file action_module.h.
|
private |
Definition at line 75 of file action_module.h.
|
private |
Definition at line 73 of file action_module.h.
|
private |
Definition at line 125 of file action_module.h.
|
private |
Definition at line 124 of file action_module.h.
|
private |
Definition at line 102 of file action_module.h.
|
private |
Definition at line 105 of file action_module.h.
|
private |
Definition at line 120 of file action_module.h.
|
private |
Definition at line 77 of file action_module.h.