Public Member Functions | Private Member Functions | Private Attributes | List of all members
thormang3::ActionModule Class Reference

#include <action_module.h>

Inheritance diagram for thormang3::ActionModule:
Inheritance graph
[legend]

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 >
Singletonoperator= (Singleton const &)
 
 Singleton (Singleton const &)
 
 Singleton ()
 
- Protected Attributes inherited from robotis_framework::MotionModule
ControlMode control_mode_
 
bool enable_
 
std::string module_name_
 

Detailed Description

Definition at line 49 of file action_module.h.

Constructor & Destructor Documentation

ActionModule::ActionModule ( )

Definition at line 37 of file action_module.cpp.

ActionModule::~ActionModule ( )
virtual

Definition at line 75 of file action_module.cpp.

Member Function Documentation

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.

std::string ActionModule::convertIntToString ( int  n)
private

Definition at line 31 of file action_module.cpp.

int ActionModule::convertRadTow4095 ( double  rad)
private

Definition at line 317 of file action_module.cpp.

double ActionModule::convertw4095ToRad ( int  w4095)
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.

void ActionModule::initialize ( const int  control_cycle_msec,
robotis_framework::Robot robot 
)
virtual

Implements robotis_framework::MotionModule.

Definition at line 84 of file action_module.cpp.

bool ActionModule::isRunning ( )
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.

bool ActionModule::isRunningServiceCallback ( thormang3_action_module_msgs::IsRunning::Request &  req,
thormang3_action_module_msgs::IsRunning::Response &  res 
)
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.

void ActionModule::onModuleDisable ( )
virtual

Reimplemented from robotis_framework::MotionModule.

Definition at line 301 of file action_module.cpp.

void ActionModule::onModuleEnable ( )
virtual

Reimplemented from robotis_framework::MotionModule.

Definition at line 296 of file action_module.cpp.

void ActionModule::pageNumberCallback ( const std_msgs::Int32::ConstPtr &  msg)
private

Definition at line 143 of file action_module.cpp.

void ActionModule::process ( std::map< std::string, robotis_framework::Dynamixel * >  dxls,
std::map< std::string, double >  sensors 
)
virtual

Implements robotis_framework::MotionModule.

Definition at line 241 of file action_module.cpp.

void ActionModule::publishDoneMsg ( std::string  msg)
private

Definition at line 1042 of file action_module.cpp.

void ActionModule::publishStatusMsg ( unsigned int  type,
std::string  msg 
)
private

Definition at line 1031 of file action_module.cpp.

void ActionModule::queueThread ( )
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.

void ActionModule::setChecksum ( action_file_define::Page page)
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.

void ActionModule::startActionCallback ( const thormang3_action_module_msgs::StartAction::ConstPtr &  msg)
private

Definition at line 183 of file action_module.cpp.

void ActionModule::stop ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 307 of file action_module.cpp.

bool ActionModule::verifyChecksum ( action_file_define::Page page)
private

Definition at line 327 of file action_module.cpp.

Member Data Documentation

FILE* thormang3::ActionModule::action_file_
private

Definition at line 109 of file action_module.h.

std::map<std::string, bool> thormang3::ActionModule::action_joints_enable_
private

Definition at line 99 of file action_module.h.

bool thormang3::ActionModule::action_module_enabled_
private

Definition at line 122 of file action_module.h.

std::map<std::string, robotis_framework::DynamixelState *> thormang3::ActionModule::action_result_
private

Definition at line 100 of file action_module.h.

int thormang3::ActionModule::control_cycle_msec_
private

Definition at line 101 of file action_module.h.

action_file_define::Step thormang3::ActionModule::current_step_
private

Definition at line 112 of file action_module.h.

ros::Publisher thormang3::ActionModule::done_msg_pub_
private

Definition at line 105 of file action_module.h.

bool thormang3::ActionModule::first_driving_start_
private

Definition at line 115 of file action_module.h.

std::map<int, std::string> thormang3::ActionModule::joint_id_to_name_
private

Definition at line 108 of file action_module.h.

std::map<std::string, int> thormang3::ActionModule::joint_name_to_id_
private

Definition at line 107 of file action_module.h.

const int thormang3::ActionModule::MAIN_SECTION
private

Definition at line 127 of file action_module.h.

action_file_define::Page thormang3::ActionModule::next_play_page_
private

Definition at line 111 of file action_module.h.

const int thormang3::ActionModule::NONE_ZERO_FINISH
private

Definition at line 131 of file action_module.h.

int thormang3::ActionModule::page_step_count_
private

Definition at line 116 of file action_module.h.

const int thormang3::ActionModule::PAUSE_SECTION
private

Definition at line 129 of file action_module.h.

action_file_define::Page thormang3::ActionModule::play_page_
private

Definition at line 110 of file action_module.h.

int thormang3::ActionModule::play_page_idx_
private

Definition at line 114 of file action_module.h.

bool thormang3::ActionModule::playing_
private

Definition at line 118 of file action_module.h.

bool thormang3::ActionModule::playing_finished_
private

Definition at line 120 of file action_module.h.

const int thormang3::ActionModule::POST_SECTION
private

Definition at line 128 of file action_module.h.

const int thormang3::ActionModule::PRE_SECTION
private

Definition at line 126 of file action_module.h.

bool thormang3::ActionModule::present_running_
private

Definition at line 124 of file action_module.h.

bool thormang3::ActionModule::previous_running_
private

Definition at line 123 of file action_module.h.

boost::thread thormang3::ActionModule::queue_thread_
private

Definition at line 102 of file action_module.h.

ros::Publisher thormang3::ActionModule::status_msg_pub_
private

Definition at line 104 of file action_module.h.

bool thormang3::ActionModule::stop_playing_
private

Definition at line 119 of file action_module.h.

const int thormang3::ActionModule::ZERO_FINISH
private

Definition at line 130 of file action_module.h.


The documentation for this class was generated from the following files:


thormang3_action_module
Author(s): Kayman , Jay Song
autogenerated on Mon Jun 10 2019 15:37:44