Public Types | Public Slots | Signals | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
thormang3_offset_tuner_client::QNode Class Reference

#include <qnode.hpp>

Inheritance diagram for thormang3_offset_tuner_client::QNode:
Inheritance graph
[legend]

Public Types

enum  LogLevel {
  Debug, Info, Warn, Error,
  Fatal
}
 

Public Slots

void getPresentJointOffsetData ()
 

Signals

void loggingUpdated ()
 
void rosShutdown ()
 
void update_present_joint_offset_data (thormang3_offset_tuner_msgs::JointOffsetPositionData msg)
 

Public Member Functions

bool init ()
 
bool init (const std::string &master_url, const std::string &host_url)
 
bool is_refresh ()
 
void log (const LogLevel &level, const std::string &msg)
 
QStringListModel * loggingModel ()
 
 QNode (int argc, char **argv)
 
void run ()
 
void send_command_msg (std_msgs::String msg)
 
void send_joint_offset_data_msg (thormang3_offset_tuner_msgs::JointOffsetData msg)
 
void send_torque_enable_msg (thormang3_offset_tuner_msgs::JointTorqueOnOffArray msg)
 
virtual ~QNode ()
 

Public Attributes

std::map< int, std::string > body_offset_group
 
std::map< int, std::string > left_arm_offset_group
 
std::map< int, std::string > legs_offset_group
 
std::map< int, std::string > right_arm_offset_group
 

Private Member Functions

void ParseOffsetGroup (const std::string &path)
 

Private Attributes

ros::Publisher command_pub_
 
ros::ServiceClient get_present_joint_offset_data_client_
 
int init_argc_
 
char ** init_argv_
 
bool is_refresh_
 
ros::Publisher joint_offset_data_pub_
 
QStringListModel logging_model_
 
ros::Publisher torque_enable_pub_
 

Detailed Description

Definition at line 59 of file qnode.hpp.

Member Enumeration Documentation

Enumerator
Debug 
Info 
Warn 
Error 
Fatal 

Definition at line 63 of file qnode.hpp.

Constructor & Destructor Documentation

thormang3_offset_tuner_client::QNode::QNode ( int  argc,
char **  argv 
)

Definition at line 43 of file qnode.cpp.

thormang3_offset_tuner_client::QNode::~QNode ( )
virtual

Definition at line 50 of file qnode.cpp.

Member Function Documentation

void thormang3_offset_tuner_client::QNode::getPresentJointOffsetData ( )
slot

Definition at line 122 of file qnode.cpp.

bool thormang3_offset_tuner_client::QNode::init ( )

Definition at line 60 of file qnode.cpp.

bool thormang3_offset_tuner_client::QNode::init ( const std::string &  master_url,
const std::string &  host_url 
)
bool thormang3_offset_tuner_client::QNode::is_refresh ( )
inline

Definition at line 86 of file qnode.hpp.

void thormang3_offset_tuner_client::QNode::log ( const LogLevel level,
const std::string &  msg 
)

Definition at line 146 of file qnode.cpp.

QStringListModel* thormang3_offset_tuner_client::QNode::loggingModel ( )
inline

Definition at line 77 of file qnode.hpp.

void thormang3_offset_tuner_client::QNode::loggingUpdated ( )
signal
void thormang3_offset_tuner_client::QNode::ParseOffsetGroup ( const std::string &  path)
private

Definition at line 188 of file qnode.cpp.

void thormang3_offset_tuner_client::QNode::rosShutdown ( )
signal
void thormang3_offset_tuner_client::QNode::run ( )

Definition at line 84 of file qnode.cpp.

void thormang3_offset_tuner_client::QNode::send_command_msg ( std_msgs::String  msg)

Definition at line 112 of file qnode.cpp.

void thormang3_offset_tuner_client::QNode::send_joint_offset_data_msg ( thormang3_offset_tuner_msgs::JointOffsetData  msg)

Definition at line 105 of file qnode.cpp.

void thormang3_offset_tuner_client::QNode::send_torque_enable_msg ( thormang3_offset_tuner_msgs::JointTorqueOnOffArray  msg)

Definition at line 98 of file qnode.cpp.

void thormang3_offset_tuner_client::QNode::update_present_joint_offset_data ( thormang3_offset_tuner_msgs::JointOffsetPositionData  msg)
signal

Member Data Documentation

std::map<int, std::string> thormang3_offset_tuner_client::QNode::body_offset_group

Definition at line 94 of file qnode.hpp.

ros::Publisher thormang3_offset_tuner_client::QNode::command_pub_
private

Definition at line 115 of file qnode.hpp.

ros::ServiceClient thormang3_offset_tuner_client::QNode::get_present_joint_offset_data_client_
private

Definition at line 117 of file qnode.hpp.

int thormang3_offset_tuner_client::QNode::init_argc_
private

Definition at line 108 of file qnode.hpp.

char** thormang3_offset_tuner_client::QNode::init_argv_
private

Definition at line 109 of file qnode.hpp.

bool thormang3_offset_tuner_client::QNode::is_refresh_
private

Definition at line 110 of file qnode.hpp.

ros::Publisher thormang3_offset_tuner_client::QNode::joint_offset_data_pub_
private

Definition at line 113 of file qnode.hpp.

std::map<int, std::string> thormang3_offset_tuner_client::QNode::left_arm_offset_group

Definition at line 92 of file qnode.hpp.

std::map<int, std::string> thormang3_offset_tuner_client::QNode::legs_offset_group

Definition at line 93 of file qnode.hpp.

QStringListModel thormang3_offset_tuner_client::QNode::logging_model_
private

Definition at line 111 of file qnode.hpp.

std::map<int, std::string> thormang3_offset_tuner_client::QNode::right_arm_offset_group

Definition at line 91 of file qnode.hpp.

ros::Publisher thormang3_offset_tuner_client::QNode::torque_enable_pub_
private

Definition at line 114 of file qnode.hpp.


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


thormang3_offset_tuner_client
Author(s): Kayman
autogenerated on Mon Jun 10 2019 15:38:36