Public Member Functions | Private Attributes | List of all members
OpenManipulatorTeleop Class Reference

#include <open_manipulator_teleop_joystick.h>

Public Member Functions

void disableWaitingForEnter (void)
 
std::vector< double > getPresentJointAngle ()
 
std::vector< double > getPresentJointAngle ()
 
std::vector< double > getPresentKinematicsPose ()
 
std::vector< double > getPresentKinematicsPose ()
 
void initClient ()
 
void initClient ()
 
void initSubscriber ()
 
void initSubscriber ()
 
void jointStatesCallback (const sensor_msgs::JointState::ConstPtr &msg)
 
void jointStatesCallback (const sensor_msgs::JointState::ConstPtr &msg)
 
void joyCallback (const sensor_msgs::Joy::ConstPtr &msg)
 
void kinematicsPoseCallback (const open_manipulator_msgs::KinematicsPose::ConstPtr &msg)
 
void kinematicsPoseCallback (const open_manipulator_msgs::KinematicsPose::ConstPtr &msg)
 
 OpenManipulatorTeleop ()
 
 OpenManipulatorTeleop ()
 
void printText ()
 
void restoreTerminalSettings (void)
 
void setGoal (const char *str)
 
void setGoal (char ch)
 
bool setJointSpacePath (std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
 
bool setJointSpacePath (std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
 
bool setJointSpacePathFromPresent (std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
 
bool setTaskSpacePathFromPresentPositionOnly (std::vector< double > kinematics_pose, double path_time)
 
bool setTaskSpacePathFromPresentPositionOnly (std::vector< double > kinematics_pose, double path_time)
 
bool setToolControl (std::vector< double > joint_angle)
 
bool setToolControl (std::vector< double > joint_angle)
 
 ~OpenManipulatorTeleop ()
 
 ~OpenManipulatorTeleop ()
 

Private Attributes

ros::ServiceClient goal_joint_space_path_client_
 
ros::ServiceClient goal_joint_space_path_from_present_client_
 
ros::ServiceClient goal_task_space_path_from_present_position_only_client_
 
ros::ServiceClient goal_tool_control_client_
 
ros::Subscriber joint_states_sub_
 
ros::Subscriber joy_command_sub_
 
ros::Subscriber kinematics_pose_sub_
 
ros::NodeHandle node_handle_
 
struct termios oldt_
 
std::vector< double > present_joint_angle_
 
std::vector< double > present_kinematic_position_
 
ros::NodeHandle priv_node_handle_
 

Detailed Description

Definition at line 17 of file open_manipulator_teleop_joystick.h.

Constructor & Destructor Documentation

OpenManipulatorTeleop::OpenManipulatorTeleop ( )

Definition at line 21 of file open_manipulator_teleop_joystick.cpp.

OpenManipulatorTeleop::~OpenManipulatorTeleop ( )

Definition at line 34 of file open_manipulator_teleop_joystick.cpp.

OpenManipulatorTeleop::OpenManipulatorTeleop ( )
OpenManipulatorTeleop::~OpenManipulatorTeleop ( )

Member Function Documentation

void OpenManipulatorTeleop::disableWaitingForEnter ( void  )

Definition at line 364 of file open_manipulator_teleop_keyboard.cpp.

std::vector<double> OpenManipulatorTeleop::getPresentJointAngle ( )
std::vector< double > OpenManipulatorTeleop::getPresentJointAngle ( )

Definition at line 94 of file open_manipulator_teleop_joystick.cpp.

std::vector<double> OpenManipulatorTeleop::getPresentKinematicsPose ( )
std::vector< double > OpenManipulatorTeleop::getPresentKinematicsPose ( )

Definition at line 98 of file open_manipulator_teleop_joystick.cpp.

void OpenManipulatorTeleop::initClient ( )

Definition at line 42 of file open_manipulator_teleop_joystick.cpp.

void OpenManipulatorTeleop::initClient ( )
void OpenManipulatorTeleop::initSubscriber ( )

Definition at line 49 of file open_manipulator_teleop_joystick.cpp.

void OpenManipulatorTeleop::initSubscriber ( )
void OpenManipulatorTeleop::jointStatesCallback ( const sensor_msgs::JointState::ConstPtr &  msg)

Definition at line 56 of file open_manipulator_teleop_joystick.cpp.

void OpenManipulatorTeleop::jointStatesCallback ( const sensor_msgs::JointState::ConstPtr &  msg)
void OpenManipulatorTeleop::joyCallback ( const sensor_msgs::Joy::ConstPtr &  msg)

Definition at line 79 of file open_manipulator_teleop_joystick.cpp.

void OpenManipulatorTeleop::kinematicsPoseCallback ( const open_manipulator_msgs::KinematicsPose::ConstPtr &  msg)

Definition at line 71 of file open_manipulator_teleop_joystick.cpp.

void OpenManipulatorTeleop::kinematicsPoseCallback ( const open_manipulator_msgs::KinematicsPose::ConstPtr &  msg)
void OpenManipulatorTeleop::printText ( )

Definition at line 146 of file open_manipulator_teleop_keyboard.cpp.

void OpenManipulatorTeleop::restoreTerminalSettings ( void  )

Definition at line 359 of file open_manipulator_teleop_keyboard.cpp.

void OpenManipulatorTeleop::setGoal ( const char *  str)

Definition at line 146 of file open_manipulator_teleop_joystick.cpp.

void OpenManipulatorTeleop::setGoal ( char  ch)

Definition at line 190 of file open_manipulator_teleop_keyboard.cpp.

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

Definition at line 103 of file open_manipulator_teleop_joystick.cpp.

bool OpenManipulatorTeleop::setJointSpacePath ( std::vector< std::string >  joint_name,
std::vector< double >  joint_angle,
double  path_time 
)
bool OpenManipulatorTeleop::setJointSpacePathFromPresent ( std::vector< std::string >  joint_name,
std::vector< double >  joint_angle,
double  path_time 
)

Definition at line 89 of file open_manipulator_teleop_keyboard.cpp.

bool OpenManipulatorTeleop::setTaskSpacePathFromPresentPositionOnly ( std::vector< double >  kinematics_pose,
double  path_time 
)
bool OpenManipulatorTeleop::setTaskSpacePathFromPresentPositionOnly ( std::vector< double >  kinematics_pose,
double  path_time 
)

Definition at line 130 of file open_manipulator_teleop_joystick.cpp.

bool OpenManipulatorTeleop::setToolControl ( std::vector< double >  joint_angle)
bool OpenManipulatorTeleop::setToolControl ( std::vector< double >  joint_angle)

Definition at line 117 of file open_manipulator_teleop_joystick.cpp.

Member Data Documentation

ros::ServiceClient OpenManipulatorTeleop::goal_joint_space_path_client_
private

Definition at line 25 of file open_manipulator_teleop_joystick.h.

ros::ServiceClient OpenManipulatorTeleop::goal_joint_space_path_from_present_client_
private

Definition at line 23 of file open_manipulator_teleop_keyboard.h.

ros::ServiceClient OpenManipulatorTeleop::goal_task_space_path_from_present_position_only_client_
private

Definition at line 24 of file open_manipulator_teleop_joystick.h.

ros::ServiceClient OpenManipulatorTeleop::goal_tool_control_client_
private

Definition at line 26 of file open_manipulator_teleop_joystick.h.

ros::Subscriber OpenManipulatorTeleop::joint_states_sub_
private

Definition at line 28 of file open_manipulator_teleop_joystick.h.

ros::Subscriber OpenManipulatorTeleop::joy_command_sub_
private

Definition at line 30 of file open_manipulator_teleop_joystick.h.

ros::Subscriber OpenManipulatorTeleop::kinematics_pose_sub_
private

Definition at line 29 of file open_manipulator_teleop_joystick.h.

ros::NodeHandle OpenManipulatorTeleop::node_handle_
private

Definition at line 21 of file open_manipulator_teleop_joystick.h.

struct termios OpenManipulatorTeleop::oldt_
private

Definition at line 34 of file open_manipulator_teleop_keyboard.h.

std::vector< double > OpenManipulatorTeleop::present_joint_angle_
private

Definition at line 32 of file open_manipulator_teleop_joystick.h.

std::vector< double > OpenManipulatorTeleop::present_kinematic_position_
private

Definition at line 33 of file open_manipulator_teleop_joystick.h.

ros::NodeHandle OpenManipulatorTeleop::priv_node_handle_
private

Definition at line 22 of file open_manipulator_teleop_joystick.h.


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


open_manipulator_teleop
Author(s): Darby Lim , Hye-Jong KIM , Ryan Shim , Yong-Ho Na
autogenerated on Mon Jun 10 2019 14:12:20