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

#include <qnode.hpp>

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

Public Types

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

Signals

void rosShutdown ()
 

Public Member Functions

bool getOpenManipulatorActuatorState ()
 
bool getOpenManipulatorMovingState ()
 
std::vector< double > getPresentJointAngle ()
 
std::vector< double > getPresentKinematicsPose ()
 
bool init ()
 
void jointStatesCallback (const sensor_msgs::JointState::ConstPtr &msg)
 
void kinematicsPoseCallback (const open_manipulator_msgs::KinematicsPose::ConstPtr &msg)
 
void log (const LogLevel &level, const std::string &msg)
 
QStringListModel * loggingModel ()
 
void manipulatorStatesCallback (const open_manipulator_msgs::OpenManipulatorState::ConstPtr &msg)
 
 QNode (int argc, char **argv)
 
void run ()
 
bool setActuatorState (bool actuator_state)
 
bool setDrawingTrajectory (std::string name, std::vector< double > arg, double path_time)
 
bool setJointSpacePath (std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
 
void setOption (std::string opt)
 
bool setTaskSpacePath (std::vector< double > kinematics_pose, double path_time)
 
bool setToolControl (std::vector< double > joint_angle)
 
virtual ~QNode ()
 

Private Attributes

ros::ServiceClient goal_drawing_trajectory_client_
 
ros::ServiceClient goal_joint_space_path_client_
 
ros::ServiceClient goal_task_space_path_position_only_client_
 
ros::ServiceClient goal_tool_control_client_
 
int init_argc
 
char ** init_argv
 
open_manipulator_msgs::KinematicsPose kinematics_pose_
 
QStringListModel logging_model
 
bool open_manipulator_actuator_enabled_
 
bool open_manipulator_is_moving_
 
ros::Subscriber open_manipulator_joint_states_sub_
 
ros::Subscriber open_manipulator_kinematics_pose_sub_
 
ros::Publisher open_manipulator_option_pub_
 
ros::Subscriber open_manipulator_states_sub_
 
std::vector< double > present_joint_angle_
 
std::vector< double > present_kinematic_position_
 
ros::ServiceClient set_actuator_state_client_
 

Detailed Description

Definition at line 60 of file qnode.hpp.

Member Enumeration Documentation

◆ LogLevel

Enumerator
Debug 
Info 
Warn 
Error 
Fatal 

Definition at line 71 of file qnode.hpp.

Constructor & Destructor Documentation

◆ QNode()

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

Definition at line 40 of file qnode.cpp.

◆ ~QNode()

open_manipulator_control_gui::QNode::~QNode ( )
virtual

Definition at line 47 of file qnode.cpp.

Member Function Documentation

◆ getOpenManipulatorActuatorState()

bool open_manipulator_control_gui::QNode::getOpenManipulatorActuatorState ( )

Definition at line 141 of file qnode.cpp.

◆ getOpenManipulatorMovingState()

bool open_manipulator_control_gui::QNode::getOpenManipulatorMovingState ( )

Definition at line 137 of file qnode.cpp.

◆ getPresentJointAngle()

std::vector< double > open_manipulator_control_gui::QNode::getPresentJointAngle ( )

Definition at line 129 of file qnode.cpp.

◆ getPresentKinematicsPose()

std::vector< double > open_manipulator_control_gui::QNode::getPresentKinematicsPose ( )

Definition at line 133 of file qnode.cpp.

◆ init()

bool open_manipulator_control_gui::QNode::init ( )

Definition at line 55 of file qnode.cpp.

◆ jointStatesCallback()

void open_manipulator_control_gui::QNode::jointStatesCallback ( const sensor_msgs::JointState::ConstPtr &  msg)

Definition at line 102 of file qnode.cpp.

◆ kinematicsPoseCallback()

void open_manipulator_control_gui::QNode::kinematicsPoseCallback ( const open_manipulator_msgs::KinematicsPose::ConstPtr &  msg)

Definition at line 117 of file qnode.cpp.

◆ log()

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

◆ loggingModel()

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

Definition at line 79 of file qnode.hpp.

◆ manipulatorStatesCallback()

void open_manipulator_control_gui::QNode::manipulatorStatesCallback ( const open_manipulator_msgs::OpenManipulatorState::ConstPtr &  msg)

Definition at line 90 of file qnode.cpp.

◆ rosShutdown

void open_manipulator_control_gui::QNode::rosShutdown ( )
signal

◆ run()

void open_manipulator_control_gui::QNode::run ( )

Definition at line 80 of file qnode.cpp.

◆ setActuatorState()

bool open_manipulator_control_gui::QNode::setActuatorState ( bool  actuator_state)

Definition at line 220 of file qnode.cpp.

◆ setDrawingTrajectory()

bool open_manipulator_control_gui::QNode::setDrawingTrajectory ( std::string  name,
std::vector< double >  arg,
double  path_time 
)

Definition at line 191 of file qnode.cpp.

◆ setJointSpacePath()

bool open_manipulator_control_gui::QNode::setJointSpacePath ( std::vector< std::string >  joint_name,
std::vector< double >  joint_angle,
double  path_time 
)

Definition at line 153 of file qnode.cpp.

◆ setOption()

void open_manipulator_control_gui::QNode::setOption ( std::string  opt)

Definition at line 146 of file qnode.cpp.

◆ setTaskSpacePath()

bool open_manipulator_control_gui::QNode::setTaskSpacePath ( std::vector< double >  kinematics_pose,
double  path_time 
)

Definition at line 167 of file qnode.cpp.

◆ setToolControl()

bool open_manipulator_control_gui::QNode::setToolControl ( std::vector< double >  joint_angle)

Definition at line 207 of file qnode.cpp.

Member Data Documentation

◆ goal_drawing_trajectory_client_

ros::ServiceClient open_manipulator_control_gui::QNode::goal_drawing_trajectory_client_
private

Definition at line 116 of file qnode.hpp.

◆ goal_joint_space_path_client_

ros::ServiceClient open_manipulator_control_gui::QNode::goal_joint_space_path_client_
private

Definition at line 112 of file qnode.hpp.

◆ goal_task_space_path_position_only_client_

ros::ServiceClient open_manipulator_control_gui::QNode::goal_task_space_path_position_only_client_
private

Definition at line 113 of file qnode.hpp.

◆ goal_tool_control_client_

ros::ServiceClient open_manipulator_control_gui::QNode::goal_tool_control_client_
private

Definition at line 114 of file qnode.hpp.

◆ init_argc

int open_manipulator_control_gui::QNode::init_argc
private

Definition at line 102 of file qnode.hpp.

◆ init_argv

char** open_manipulator_control_gui::QNode::init_argv
private

Definition at line 103 of file qnode.hpp.

◆ kinematics_pose_

open_manipulator_msgs::KinematicsPose open_manipulator_control_gui::QNode::kinematics_pose_
private

Definition at line 120 of file qnode.hpp.

◆ logging_model

QStringListModel open_manipulator_control_gui::QNode::logging_model
private

Definition at line 104 of file qnode.hpp.

◆ open_manipulator_actuator_enabled_

bool open_manipulator_control_gui::QNode::open_manipulator_actuator_enabled_
private

Definition at line 123 of file qnode.hpp.

◆ open_manipulator_is_moving_

bool open_manipulator_control_gui::QNode::open_manipulator_is_moving_
private

Definition at line 122 of file qnode.hpp.

◆ open_manipulator_joint_states_sub_

ros::Subscriber open_manipulator_control_gui::QNode::open_manipulator_joint_states_sub_
private

Definition at line 109 of file qnode.hpp.

◆ open_manipulator_kinematics_pose_sub_

ros::Subscriber open_manipulator_control_gui::QNode::open_manipulator_kinematics_pose_sub_
private

Definition at line 110 of file qnode.hpp.

◆ open_manipulator_option_pub_

ros::Publisher open_manipulator_control_gui::QNode::open_manipulator_option_pub_
private

Definition at line 106 of file qnode.hpp.

◆ open_manipulator_states_sub_

ros::Subscriber open_manipulator_control_gui::QNode::open_manipulator_states_sub_
private

Definition at line 108 of file qnode.hpp.

◆ present_joint_angle_

std::vector<double> open_manipulator_control_gui::QNode::present_joint_angle_
private

Definition at line 118 of file qnode.hpp.

◆ present_kinematic_position_

std::vector<double> open_manipulator_control_gui::QNode::present_kinematic_position_
private

Definition at line 119 of file qnode.hpp.

◆ set_actuator_state_client_

ros::ServiceClient open_manipulator_control_gui::QNode::set_actuator_state_client_
private

Definition at line 115 of file qnode.hpp.


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


open_manipulator_control_gui
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Mon Feb 28 2022 23:02:15