#include <thormang3_offset_tuner_server.h>

Public Member Functions | |
| void | commandCallback (const std_msgs::String::ConstPtr &msg) |
| bool | getPresentJointOffsetDataServiceCallback (thormang3_offset_tuner_msgs::GetPresentJointOffsetData::Request &req, thormang3_offset_tuner_msgs::GetPresentJointOffsetData::Response &res) |
| bool | initialize () |
| void | jointOffsetDataCallback (const thormang3_offset_tuner_msgs::JointOffsetData::ConstPtr &msg) |
| void | jointTorqueOnOffCallback (const thormang3_offset_tuner_msgs::JointTorqueOnOffArray::ConstPtr &msg) |
| void | moveToInitPose () |
| OffsetTunerServer () | |
| void | stringMsgsCallBack (const std_msgs::String::ConstPtr &msg) |
| ~OffsetTunerServer () | |
Private Member Functions | |
| void | setCtrlModule (std::string module) |
Private Attributes | |
| ros::Subscriber | command_sub_ |
| robotis_framework::RobotisController * | controller_ |
| std::string | init_file_ |
| ros::Subscriber | joint_offset_data_sub_ |
| ros::Subscriber | joint_torque_enable_sub_ |
| ros::ServiceServer | offset_data_server_ |
| std::string | offset_file_ |
| std::string | robot_file_ |
| std::map< std::string, JointOffsetData * > | robot_offset_data_ |
| std::map< std::string, bool > | robot_torque_enable_data_ |
| ros::Subscriber | send_tra_sub_ |
Additional Inherited Members | |
Static Public Member Functions inherited from robotis_framework::Singleton< OffsetTunerServer > | |
| static void | destroyInstance () |
| static T * | getInstance () |
Protected Member Functions inherited from robotis_framework::Singleton< OffsetTunerServer > | |
| Singleton & | operator= (Singleton const &) |
| Singleton (Singleton const &) | |
| Singleton () | |
Definition at line 73 of file thormang3_offset_tuner_server.h.
| OffsetTunerServer::OffsetTunerServer | ( | ) |
Definition at line 31 of file thormang3_offset_tuner_server.cpp.
| OffsetTunerServer::~OffsetTunerServer | ( | ) |
Definition at line 39 of file thormang3_offset_tuner_server.cpp.
| void OffsetTunerServer::commandCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 273 of file thormang3_offset_tuner_server.cpp.
| bool OffsetTunerServer::getPresentJointOffsetDataServiceCallback | ( | thormang3_offset_tuner_msgs::GetPresentJointOffsetData::Request & | req, |
| thormang3_offset_tuner_msgs::GetPresentJointOffsetData::Response & | res | ||
| ) |
Definition at line 418 of file thormang3_offset_tuner_server.cpp.
| bool OffsetTunerServer::initialize | ( | ) |
Definition at line 62 of file thormang3_offset_tuner_server.cpp.
| void OffsetTunerServer::jointOffsetDataCallback | ( | const thormang3_offset_tuner_msgs::JointOffsetData::ConstPtr & | msg | ) |
Definition at line 316 of file thormang3_offset_tuner_server.cpp.
| void OffsetTunerServer::jointTorqueOnOffCallback | ( | const thormang3_offset_tuner_msgs::JointTorqueOnOffArray::ConstPtr & | msg | ) |
Definition at line 372 of file thormang3_offset_tuner_server.cpp.
| void OffsetTunerServer::moveToInitPose | ( | ) |
Definition at line 205 of file thormang3_offset_tuner_server.cpp.
|
private |
Definition at line 43 of file thormang3_offset_tuner_server.cpp.
| void OffsetTunerServer::stringMsgsCallBack | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 268 of file thormang3_offset_tuner_server.cpp.
|
private |
Definition at line 90 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 78 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 80 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 88 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 89 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 91 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 82 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 81 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 85 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 84 of file thormang3_offset_tuner_server.h.
|
private |
Definition at line 87 of file thormang3_offset_tuner_server.h.