#include <qnode.hpp>
Definition at line 73 of file qnode.hpp.
Enumerator |
---|
Debug |
|
Info |
|
Warn |
|
Error |
|
Fatal |
|
Definition at line 85 of file qnode.hpp.
manipulator_h_gui::QNode::QNode |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
manipulator_h_gui::QNode::~QNode |
( |
| ) |
|
|
virtual |
void manipulator_h_gui::QNode::getJointPose |
( |
std::vector< std::string > |
joint_name | ) |
|
|
slot |
void manipulator_h_gui::QNode::getKinematicsPose |
( |
std::string |
group_name | ) |
|
|
slot |
bool manipulator_h_gui::QNode::init |
( |
| ) |
|
void manipulator_h_gui::QNode::log |
( |
const LogLevel & |
level, |
|
|
const std::string & |
msg, |
|
|
std::string |
sender = "GUI" |
|
) |
| |
QStringListModel* manipulator_h_gui::QNode::loggingModel |
( |
| ) |
|
|
inline |
void manipulator_h_gui::QNode::loggingUpdated |
( |
| ) |
|
|
signal |
void manipulator_h_gui::QNode::rosShutdown |
( |
| ) |
|
|
signal |
void manipulator_h_gui::QNode::run |
( |
| ) |
|
void manipulator_h_gui::QNode::sendIniPoseMsg |
( |
std_msgs::String |
msg | ) |
|
void manipulator_h_gui::QNode::sendJointPoseMsg |
( |
manipulator_h_base_module_msgs::JointPose |
msg | ) |
|
void manipulator_h_gui::QNode::sendKinematicsPoseMsg |
( |
manipulator_h_base_module_msgs::KinematicsPose |
msg | ) |
|
void manipulator_h_gui::QNode::sendSetModeMsg |
( |
std_msgs::String |
msg | ) |
|
void manipulator_h_gui::QNode::statusMsgCallback |
( |
const robotis_controller_msgs::StatusMsg::ConstPtr & |
msg | ) |
|
void manipulator_h_gui::QNode::updateCurrentJointPose |
( |
manipulator_h_base_module_msgs::JointPose |
| ) |
|
|
signal |
void manipulator_h_gui::QNode::updateCurrentKinematicsPose |
( |
manipulator_h_base_module_msgs::KinematicsPose |
| ) |
|
|
signal |
int manipulator_h_gui::QNode::init_argc_ |
|
private |
char** manipulator_h_gui::QNode::init_argv_ |
|
private |
QStringListModel manipulator_h_gui::QNode::logging_model_ |
|
private |
The documentation for this class was generated from the following files: