#include <qnode.hpp>
Definition at line 60 of file qnode.hpp.
Enumerator |
---|
Debug |
|
Info |
|
Warn |
|
Error |
|
Fatal |
|
Definition at line 71 of file qnode.hpp.
open_manipulator_control_gui::QNode::QNode |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
open_manipulator_control_gui::QNode::~QNode |
( |
| ) |
|
|
virtual |
bool open_manipulator_control_gui::QNode::getOpenManipulatorActuatorState |
( |
| ) |
|
bool open_manipulator_control_gui::QNode::getOpenManipulatorMovingState |
( |
| ) |
|
std::vector< double > open_manipulator_control_gui::QNode::getPresentJointAngle |
( |
| ) |
|
std::vector< double > open_manipulator_control_gui::QNode::getPresentKinematicsPose |
( |
| ) |
|
bool open_manipulator_control_gui::QNode::init |
( |
| ) |
|
void open_manipulator_control_gui::QNode::jointStatesCallback |
( |
const sensor_msgs::JointState::ConstPtr & |
msg | ) |
|
void open_manipulator_control_gui::QNode::kinematicsPoseCallback |
( |
const open_manipulator_msgs::KinematicsPose::ConstPtr & |
msg | ) |
|
void open_manipulator_control_gui::QNode::log |
( |
const LogLevel & |
level, |
|
|
const std::string & |
msg |
|
) |
| |
QStringListModel* open_manipulator_control_gui::QNode::loggingModel |
( |
| ) |
|
|
inline |
void open_manipulator_control_gui::QNode::manipulatorStatesCallback |
( |
const open_manipulator_msgs::OpenManipulatorState::ConstPtr & |
msg | ) |
|
void open_manipulator_control_gui::QNode::rosShutdown |
( |
| ) |
|
|
signal |
void open_manipulator_control_gui::QNode::run |
( |
| ) |
|
bool open_manipulator_control_gui::QNode::setActuatorState |
( |
bool |
actuator_state | ) |
|
bool open_manipulator_control_gui::QNode::setDrawingTrajectory |
( |
std::string |
name, |
|
|
std::vector< double > |
arg, |
|
|
double |
path_time |
|
) |
| |
bool open_manipulator_control_gui::QNode::setJointSpacePath |
( |
std::vector< std::string > |
joint_name, |
|
|
std::vector< double > |
joint_angle, |
|
|
double |
path_time |
|
) |
| |
void open_manipulator_control_gui::QNode::setOption |
( |
std::string |
opt | ) |
|
bool open_manipulator_control_gui::QNode::setTaskSpacePath |
( |
std::vector< double > |
kinematics_pose, |
|
|
double |
path_time |
|
) |
| |
bool open_manipulator_control_gui::QNode::setToolControl |
( |
std::vector< double > |
joint_angle | ) |
|
ros::ServiceClient open_manipulator_control_gui::QNode::goal_task_space_path_position_only_client_ |
|
private |
int open_manipulator_control_gui::QNode::init_argc |
|
private |
char** open_manipulator_control_gui::QNode::init_argv |
|
private |
open_manipulator_msgs::KinematicsPose open_manipulator_control_gui::QNode::kinematics_pose_ |
|
private |
QStringListModel open_manipulator_control_gui::QNode::logging_model |
|
private |
bool open_manipulator_control_gui::QNode::open_manipulator_actuator_enabled_ |
|
private |
bool open_manipulator_control_gui::QNode::open_manipulator_is_moving_ |
|
private |
ros::Subscriber open_manipulator_control_gui::QNode::open_manipulator_joint_states_sub_ |
|
private |
ros::Subscriber open_manipulator_control_gui::QNode::open_manipulator_kinematics_pose_sub_ |
|
private |
ros::Publisher open_manipulator_control_gui::QNode::open_manipulator_option_pub_ |
|
private |
ros::Subscriber open_manipulator_control_gui::QNode::open_manipulator_states_sub_ |
|
private |
std::vector<double> open_manipulator_control_gui::QNode::present_joint_angle_ |
|
private |
std::vector<double> open_manipulator_control_gui::QNode::present_kinematic_position_ |
|
private |
The documentation for this class was generated from the following files: