Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
robotis_framework::RobotisController Class Reference

#include <robotis_controller.h>

Inheritance diagram for robotis_framework::RobotisController:
Inheritance graph
[legend]

Public Member Functions

int action (const std::string joint_name)
 
void addMotionModule (MotionModule *module)
 
void addSensorModule (SensorModule *module)
 
int factoryReset (const std::string joint_name, uint8_t option=0, uint8_t *error=0)
 
void gazeboJointStatesCallback (const sensor_msgs::JointState::ConstPtr &msg)
 
bool getJointCtrlModuleService (robotis_controller_msgs::GetJointModule::Request &req, robotis_controller_msgs::GetJointModule::Response &res)
 
bool initialize (const std::string robot_file_path, const std::string init_file_path)
 
void initializeDevice (const std::string init_file_path)
 
bool isTimerRunning ()
 
void loadOffset (const std::string path)
 
int ping (const std::string joint_name, uint8_t *error=0)
 
int ping (const std::string joint_name, uint16_t *model_number, uint8_t *error=0)
 
void process ()
 
int read (const std::string joint_name, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)
 
int read1Byte (const std::string joint_name, uint16_t address, uint8_t *data, uint8_t *error=0)
 
int read2Byte (const std::string joint_name, uint16_t address, uint16_t *data, uint8_t *error=0)
 
int read4Byte (const std::string joint_name, uint16_t address, uint32_t *data, uint8_t *error=0)
 
int readCtrlItem (const std::string joint_name, const std::string item_name, uint32_t *data, uint8_t *error=0)
 
int reboot (const std::string joint_name, uint8_t *error=0)
 
int regWrite (const std::string joint_name, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)
 
void removeMotionModule (MotionModule *module)
 
void removeSensorModule (SensorModule *module)
 
 RobotisController ()
 
void setControllerModeCallback (const std_msgs::String::ConstPtr &msg)
 
void setCtrlModule (std::string module_name)
 
void setCtrlModuleCallback (const std_msgs::String::ConstPtr &msg)
 
bool setCtrlModuleService (robotis_controller_msgs::SetModule::Request &req, robotis_controller_msgs::SetModule::Response &res)
 
void setJointCtrlModuleCallback (const robotis_controller_msgs::JointCtrlModule::ConstPtr &msg)
 
bool setJointCtrlModuleService (robotis_controller_msgs::SetJointModule::Request &req, robotis_controller_msgs::SetJointModule::Response &res)
 
void setJointStatesCallback (const sensor_msgs::JointState::ConstPtr &msg)
 
void startTimer ()
 
void stopTimer ()
 
void syncWriteItemCallback (const robotis_controller_msgs::SyncWriteItem::ConstPtr &msg)
 
int write (const std::string joint_name, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)
 
int write1Byte (const std::string joint_name, uint16_t address, uint8_t data, uint8_t *error=0)
 
int write2Byte (const std::string joint_name, uint16_t address, uint16_t data, uint8_t *error=0)
 
int write4Byte (const std::string joint_name, uint16_t address, uint32_t data, uint8_t *error=0)
 
void writeControlTableCallback (const robotis_controller_msgs::WriteControlTable::ConstPtr &msg)
 
int writeCtrlItem (const std::string joint_name, const std::string item_name, uint32_t data, uint8_t *error=0)
 

Static Public Member Functions

static void * timerThread (void *param)
 
- Static Public Member Functions inherited from robotis_framework::Singleton< RobotisController >
static void destroyInstance ()
 
static T * getInstance ()
 

Public Attributes

ros::Publisher current_module_pub_
 
bool DEBUG_PRINT
 
std::map< std::string, ros::Publishergazebo_joint_effort_pub_
 
std::map< std::string, ros::Publishergazebo_joint_position_pub_
 
std::map< std::string, ros::Publishergazebo_joint_velocity_pub_
 
bool gazebo_mode_
 
std::string gazebo_robot_name_
 
ros::Publisher goal_joint_state_pub_
 
std::map< std::string, dynamixel::GroupBulkRead * > port_to_bulk_read_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_current_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_position_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_position_d_gain_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_position_i_gain_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_position_p_gain_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_velocity_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_velocity_d_gain_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_velocity_i_gain_
 
std::map< std::string, dynamixel::GroupSyncWrite * > port_to_sync_write_velocity_p_gain_
 
ros::Publisher present_joint_state_pub_
 
Robotrobot_
 

Private Member Functions

void gazeboTimerThread ()
 
void initializeSyncWrite ()
 
bool isTimerStopped ()
 
void msgQueueThread ()
 
void setCtrlModuleThread (std::string ctrl_module)
 
void setJointCtrlModuleThread (const robotis_controller_msgs::JointCtrlModule::ConstPtr &msg)
 

Private Attributes

ControllerMode controller_mode_
 
std::vector< dynamixel::GroupSyncWrite * > direct_sync_write_
 
boost::thread gazebo_thread_
 
bool init_pose_loaded_
 
bool is_timer_running_
 
std::list< MotionModule * > motion_modules_
 
boost::mutex queue_mutex_
 
boost::thread queue_thread_
 
std::list< SensorModule * > sensor_modules_
 
std::map< std::string, double > sensor_result_
 
boost::thread set_module_thread_
 
bool stop_timer_
 
pthread_t timer_thread_
 

Additional Inherited Members

- Protected Member Functions inherited from robotis_framework::Singleton< RobotisController >
Singletonoperator= (Singleton const &)
 
 Singleton (Singleton const &)
 
 Singleton ()
 

Detailed Description

Definition at line 57 of file robotis_controller.h.

Constructor & Destructor Documentation

RobotisController::RobotisController ( )

Definition at line 31 of file robotis_controller.cpp.

Member Function Documentation

int RobotisController::action ( const std::string  joint_name)

Definition at line 2204 of file robotis_controller.cpp.

void RobotisController::addMotionModule ( MotionModule module)

Definition at line 1429 of file robotis_controller.cpp.

void RobotisController::addSensorModule ( SensorModule module)

Definition at line 1451 of file robotis_controller.cpp.

int RobotisController::factoryReset ( const std::string  joint_name,
uint8_t  option = 0,
uint8_t *  error = 0 
)

Definition at line 2232 of file robotis_controller.cpp.

void RobotisController::gazeboJointStatesCallback ( const sensor_msgs::JointState::ConstPtr &  msg)

Definition at line 2149 of file robotis_controller.cpp.

void RobotisController::gazeboTimerThread ( )
private

Definition at line 603 of file robotis_controller.cpp.

bool RobotisController::getJointCtrlModuleService ( robotis_controller_msgs::GetJointModule::Request &  req,
robotis_controller_msgs::GetJointModule::Response &  res 
)

Definition at line 1697 of file robotis_controller.cpp.

bool RobotisController::initialize ( const std::string  robot_file_path,
const std::string  init_file_path 
)

Definition at line 197 of file robotis_controller.cpp.

void RobotisController::initializeDevice ( const std::string  init_file_path)

Definition at line 341 of file robotis_controller.cpp.

void RobotisController::initializeSyncWrite ( )
private

Definition at line 45 of file robotis_controller.cpp.

bool RobotisController::isTimerRunning ( )

Definition at line 840 of file robotis_controller.cpp.

bool RobotisController::isTimerStopped ( )
private

Definition at line 2174 of file robotis_controller.cpp.

void RobotisController::loadOffset ( const std::string  path)

Definition at line 845 of file robotis_controller.cpp.

void RobotisController::msgQueueThread ( )
private

Definition at line 615 of file robotis_controller.cpp.

int RobotisController::ping ( const std::string  joint_name,
uint8_t *  error = 0 
)

Definition at line 2185 of file robotis_controller.cpp.

int RobotisController::ping ( const std::string  joint_name,
uint16_t *  model_number,
uint8_t *  error = 0 
)

Definition at line 2189 of file robotis_controller.cpp.

void RobotisController::process ( )

Definition at line 873 of file robotis_controller.cpp.

int RobotisController::read ( const std::string  joint_name,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)

Definition at line 2247 of file robotis_controller.cpp.

int RobotisController::read1Byte ( const std::string  joint_name,
uint16_t  address,
uint8_t *  data,
uint8_t *  error = 0 
)

Definition at line 2311 of file robotis_controller.cpp.

int RobotisController::read2Byte ( const std::string  joint_name,
uint16_t  address,
uint16_t *  data,
uint8_t *  error = 0 
)

Definition at line 2326 of file robotis_controller.cpp.

int RobotisController::read4Byte ( const std::string  joint_name,
uint16_t  address,
uint32_t *  data,
uint8_t *  error = 0 
)

Definition at line 2341 of file robotis_controller.cpp.

int RobotisController::readCtrlItem ( const std::string  joint_name,
const std::string  item_name,
uint32_t *  data,
uint8_t *  error = 0 
)

Definition at line 2262 of file robotis_controller.cpp.

int RobotisController::reboot ( const std::string  joint_name,
uint8_t *  error = 0 
)

Definition at line 2218 of file robotis_controller.cpp.

int RobotisController::regWrite ( const std::string  joint_name,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)

Definition at line 2457 of file robotis_controller.cpp.

void RobotisController::removeMotionModule ( MotionModule module)

Definition at line 1446 of file robotis_controller.cpp.

void RobotisController::removeSensorModule ( SensorModule module)

Definition at line 1468 of file robotis_controller.cpp.

void RobotisController::setControllerModeCallback ( const std_msgs::String::ConstPtr &  msg)

Definition at line 1617 of file robotis_controller.cpp.

void RobotisController::setCtrlModule ( std::string  module_name)

Definition at line 1679 of file robotis_controller.cpp.

void RobotisController::setCtrlModuleCallback ( const std_msgs::String::ConstPtr &  msg)

Definition at line 1669 of file robotis_controller.cpp.

bool RobotisController::setCtrlModuleService ( robotis_controller_msgs::SetModule::Request &  req,
robotis_controller_msgs::SetModule::Response &  res 
)

Definition at line 1737 of file robotis_controller.cpp.

void RobotisController::setCtrlModuleThread ( std::string  ctrl_module)
private

Definition at line 1937 of file robotis_controller.cpp.

void RobotisController::setJointCtrlModuleCallback ( const robotis_controller_msgs::JointCtrlModule::ConstPtr &  msg)

Definition at line 1686 of file robotis_controller.cpp.

bool RobotisController::setJointCtrlModuleService ( robotis_controller_msgs::SetJointModule::Request &  req,
robotis_controller_msgs::SetJointModule::Response &  res 
)

Definition at line 1716 of file robotis_controller.cpp.

void RobotisController::setJointCtrlModuleThread ( const robotis_controller_msgs::JointCtrlModule::ConstPtr &  msg)
private

Definition at line 1751 of file robotis_controller.cpp.

void RobotisController::setJointStatesCallback ( const sensor_msgs::JointState::ConstPtr &  msg)

Definition at line 1638 of file robotis_controller.cpp.

void RobotisController::startTimer ( )

Definition at line 711 of file robotis_controller.cpp.

void RobotisController::stopTimer ( )

Definition at line 762 of file robotis_controller.cpp.

void RobotisController::syncWriteItemCallback ( const robotis_controller_msgs::SyncWriteItem::ConstPtr &  msg)

Definition at line 1531 of file robotis_controller.cpp.

void * RobotisController::timerThread ( void *  param)
static

Definition at line 673 of file robotis_controller.cpp.

int RobotisController::write ( const std::string  joint_name,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)

Definition at line 2356 of file robotis_controller.cpp.

int RobotisController::write1Byte ( const std::string  joint_name,
uint16_t  address,
uint8_t  data,
uint8_t *  error = 0 
)

Definition at line 2412 of file robotis_controller.cpp.

int RobotisController::write2Byte ( const std::string  joint_name,
uint16_t  address,
uint16_t  data,
uint8_t *  error = 0 
)

Definition at line 2427 of file robotis_controller.cpp.

int RobotisController::write4Byte ( const std::string  joint_name,
uint16_t  address,
uint32_t  data,
uint8_t *  error = 0 
)

Definition at line 2442 of file robotis_controller.cpp.

void RobotisController::writeControlTableCallback ( const robotis_controller_msgs::WriteControlTable::ConstPtr &  msg)

Definition at line 1473 of file robotis_controller.cpp.

int RobotisController::writeCtrlItem ( const std::string  joint_name,
const std::string  item_name,
uint32_t  data,
uint8_t *  error = 0 
)

Definition at line 2371 of file robotis_controller.cpp.

Member Data Documentation

ControllerMode robotis_framework::RobotisController::controller_mode_
private

Definition at line 69 of file robotis_controller.h.

ros::Publisher robotis_framework::RobotisController::current_module_pub_

Definition at line 109 of file robotis_controller.h.

bool robotis_framework::RobotisController::DEBUG_PRINT

Definition at line 86 of file robotis_controller.h.

std::vector<dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::direct_sync_write_
private

Definition at line 73 of file robotis_controller.h.

std::map<std::string, ros::Publisher> robotis_framework::RobotisController::gazebo_joint_effort_pub_

Definition at line 113 of file robotis_controller.h.

std::map<std::string, ros::Publisher> robotis_framework::RobotisController::gazebo_joint_position_pub_

Definition at line 111 of file robotis_controller.h.

std::map<std::string, ros::Publisher> robotis_framework::RobotisController::gazebo_joint_velocity_pub_

Definition at line 112 of file robotis_controller.h.

bool robotis_framework::RobotisController::gazebo_mode_

Definition at line 89 of file robotis_controller.h.

std::string robotis_framework::RobotisController::gazebo_robot_name_

Definition at line 90 of file robotis_controller.h.

boost::thread robotis_framework::RobotisController::gazebo_thread_
private

Definition at line 61 of file robotis_controller.h.

ros::Publisher robotis_framework::RobotisController::goal_joint_state_pub_

Definition at line 107 of file robotis_controller.h.

bool robotis_framework::RobotisController::init_pose_loaded_
private

Definition at line 65 of file robotis_controller.h.

bool robotis_framework::RobotisController::is_timer_running_
private

Definition at line 66 of file robotis_controller.h.

std::list<MotionModule *> robotis_framework::RobotisController::motion_modules_
private

Definition at line 71 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupBulkRead *> robotis_framework::RobotisController::port_to_bulk_read_

Definition at line 93 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_current_

Definition at line 98 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_position_

Definition at line 96 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_position_d_gain_

Definition at line 101 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_position_i_gain_

Definition at line 100 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_position_p_gain_

Definition at line 99 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_velocity_

Definition at line 97 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_velocity_d_gain_

Definition at line 104 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_velocity_i_gain_

Definition at line 103 of file robotis_controller.h.

std::map<std::string, dynamixel::GroupSyncWrite *> robotis_framework::RobotisController::port_to_sync_write_velocity_p_gain_

Definition at line 102 of file robotis_controller.h.

ros::Publisher robotis_framework::RobotisController::present_joint_state_pub_

Definition at line 108 of file robotis_controller.h.

boost::mutex robotis_framework::RobotisController::queue_mutex_
private

Definition at line 63 of file robotis_controller.h.

boost::thread robotis_framework::RobotisController::queue_thread_
private

Definition at line 60 of file robotis_controller.h.

Robot* robotis_framework::RobotisController::robot_

Definition at line 87 of file robotis_controller.h.

std::list<SensorModule *> robotis_framework::RobotisController::sensor_modules_
private

Definition at line 72 of file robotis_controller.h.

std::map<std::string, double> robotis_framework::RobotisController::sensor_result_
private

Definition at line 75 of file robotis_controller.h.

boost::thread robotis_framework::RobotisController::set_module_thread_
private

Definition at line 62 of file robotis_controller.h.

bool robotis_framework::RobotisController::stop_timer_
private

Definition at line 67 of file robotis_controller.h.

pthread_t robotis_framework::RobotisController::timer_thread_
private

Definition at line 68 of file robotis_controller.h.


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


robotis_controller
Author(s): Zerom , Kayman , SCH
autogenerated on Mon Jun 10 2019 14:35:12