Public Member Functions | Private Member Functions | Private Attributes | List of all members
rh_p12_rn::BaseModule Class Reference

#include <base_module.h>

Inheritance diagram for rh_p12_rn::BaseModule:
Inheritance graph
[legend]

Public Member Functions

 BaseModule ()
 
bool getItemValueCallback (rh_p12_rn_base_module_msgs::GetItemValue::Request &req, rh_p12_rn_base_module_msgs::GetItemValue::Response &res)
 
void initialize (const int control_cycle_msec, robotis_framework::Robot *robot)
 
bool isRunning ()
 
void process (std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
 
void setPosition (const robotis_controller_msgs::SyncWriteItem::ConstPtr &msg)
 
void stop ()
 
virtual ~BaseModule ()
 
- 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 ()
 

Private Member Functions

void queueThread ()
 

Private Attributes

int control_cycle_msec_
 
int goal_acceleration_
 
int goal_current_
 
int goal_position_
 
int goal_velocity_
 
bool is_moving_
 
int present_current_
 
ros::Publisher present_current_pub_
 
int present_position_
 
ros::Publisher present_position_pub_
 
int present_velocity_
 
boost::thread queue_thread_
 
robotis_framework::Robotrobot_
 
bool torque_enable_
 

Additional Inherited Members

- Static Public Member Functions inherited from robotis_framework::Singleton< BaseModule >
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< BaseModule >
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 37 of file base_module.h.

Constructor & Destructor Documentation

rh_p12_rn::BaseModule::BaseModule ( )

Definition at line 25 of file base_module.cpp.

rh_p12_rn::BaseModule::~BaseModule ( )
virtual

Definition at line 45 of file base_module.cpp.

Member Function Documentation

bool rh_p12_rn::BaseModule::getItemValueCallback ( rh_p12_rn_base_module_msgs::GetItemValue::Request &  req,
rh_p12_rn_base_module_msgs::GetItemValue::Response &  res 
)

Definition at line 97 of file base_module.cpp.

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

Implements robotis_framework::MotionModule.

Definition at line 50 of file base_module.cpp.

bool rh_p12_rn::BaseModule::isRunning ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 179 of file base_module.cpp.

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

Implements robotis_framework::MotionModule.

Definition at line 129 of file base_module.cpp.

void rh_p12_rn::BaseModule::queueThread ( )
private

Definition at line 61 of file base_module.cpp.

void rh_p12_rn::BaseModule::setPosition ( const robotis_controller_msgs::SyncWriteItem::ConstPtr &  msg)

Definition at line 88 of file base_module.cpp.

void rh_p12_rn::BaseModule::stop ( )
virtual

Implements robotis_framework::MotionModule.

Definition at line 174 of file base_module.cpp.

Member Data Documentation

int rh_p12_rn::BaseModule::control_cycle_msec_
private

Definition at line 42 of file base_module.h.

int rh_p12_rn::BaseModule::goal_acceleration_
private

Definition at line 51 of file base_module.h.

int rh_p12_rn::BaseModule::goal_current_
private

Definition at line 50 of file base_module.h.

int rh_p12_rn::BaseModule::goal_position_
private

Definition at line 48 of file base_module.h.

int rh_p12_rn::BaseModule::goal_velocity_
private

Definition at line 49 of file base_module.h.

bool rh_p12_rn::BaseModule::is_moving_
private

Definition at line 52 of file base_module.h.

int rh_p12_rn::BaseModule::present_current_
private

Definition at line 55 of file base_module.h.

ros::Publisher rh_p12_rn::BaseModule::present_current_pub_
private

Definition at line 59 of file base_module.h.

int rh_p12_rn::BaseModule::present_position_
private

Definition at line 53 of file base_module.h.

ros::Publisher rh_p12_rn::BaseModule::present_position_pub_
private

Definition at line 58 of file base_module.h.

int rh_p12_rn::BaseModule::present_velocity_
private

Definition at line 54 of file base_module.h.

boost::thread rh_p12_rn::BaseModule::queue_thread_
private

Definition at line 43 of file base_module.h.

robotis_framework::Robot* rh_p12_rn::BaseModule::robot_
private

Definition at line 45 of file base_module.h.

bool rh_p12_rn::BaseModule::torque_enable_
private

Definition at line 47 of file base_module.h.


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


rh_p12_rn_base_module
Author(s): Zerom
autogenerated on Mon Jun 10 2019 14:42:05