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

#include <open_manipulator_teleop_joystick.h>

Public Member Functions

 OpenManipulatorTeleop ()
 
 OpenManipulatorTeleop ()
 
void printText ()
 
void setGoal (char ch)
 
 ~OpenManipulatorTeleop ()
 
 ~OpenManipulatorTeleop ()
 

Private Member Functions

void disableWaitingForEnter (void)
 
std::vector< double > getPresentJointAngle ()
 
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)
 
void restoreTerminalSettings (void)
 
void setGoal (const char *str)
 
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)
 

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 36 of file open_manipulator_teleop_joystick.h.

Constructor & Destructor Documentation

◆ OpenManipulatorTeleop() [1/2]

OpenManipulatorTeleop::OpenManipulatorTeleop ( )

Definition at line 21 of file open_manipulator_teleop_joystick.cpp.

◆ ~OpenManipulatorTeleop() [1/2]

OpenManipulatorTeleop::~OpenManipulatorTeleop ( )

Definition at line 40 of file open_manipulator_teleop_joystick.cpp.

◆ OpenManipulatorTeleop() [2/2]

OpenManipulatorTeleop::OpenManipulatorTeleop ( )

◆ ~OpenManipulatorTeleop() [2/2]

OpenManipulatorTeleop::~OpenManipulatorTeleop ( )

Member Function Documentation

◆ disableWaitingForEnter()

void OpenManipulatorTeleop::disableWaitingForEnter ( void  )
private

Definition at line 364 of file open_manipulator_teleop_keyboard.cpp.

◆ getPresentJointAngle()

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

Definition at line 85 of file open_manipulator_teleop_keyboard.cpp.

◆ getPresentKinematicsPose()

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

Definition at line 90 of file open_manipulator_teleop_keyboard.cpp.

◆ initClient() [1/2]

void OpenManipulatorTeleop::initClient ( )
private

Definition at line 46 of file open_manipulator_teleop_joystick.cpp.

◆ initClient() [2/2]

void OpenManipulatorTeleop::initClient ( )
private

◆ initSubscriber() [1/2]

void OpenManipulatorTeleop::initSubscriber ( )
private

Definition at line 53 of file open_manipulator_teleop_joystick.cpp.

◆ initSubscriber() [2/2]

void OpenManipulatorTeleop::initSubscriber ( )
private

◆ jointStatesCallback() [1/2]

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

Definition at line 60 of file open_manipulator_teleop_joystick.cpp.

◆ jointStatesCallback() [2/2]

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

◆ joyCallback()

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

Definition at line 79 of file open_manipulator_teleop_joystick.cpp.

◆ kinematicsPoseCallback() [1/2]

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

Definition at line 74 of file open_manipulator_teleop_joystick.cpp.

◆ kinematicsPoseCallback() [2/2]

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

◆ printText()

void OpenManipulatorTeleop::printText ( )

Definition at line 152 of file open_manipulator_teleop_keyboard.cpp.

◆ restoreTerminalSettings()

void OpenManipulatorTeleop::restoreTerminalSettings ( void  )
private

Definition at line 359 of file open_manipulator_teleop_keyboard.cpp.

◆ setGoal() [1/2]

void OpenManipulatorTeleop::setGoal ( char  ch)

Definition at line 195 of file open_manipulator_teleop_keyboard.cpp.

◆ setGoal() [2/2]

void OpenManipulatorTeleop::setGoal ( const char *  str)
private

Definition at line 137 of file open_manipulator_teleop_joystick.cpp.

◆ setJointSpacePath() [1/2]

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

Definition at line 94 of file open_manipulator_teleop_joystick.cpp.

◆ setJointSpacePath() [2/2]

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

◆ setJointSpacePathFromPresent()

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

Definition at line 95 of file open_manipulator_teleop_keyboard.cpp.

◆ setTaskSpacePathFromPresentPositionOnly() [1/2]

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

Definition at line 121 of file open_manipulator_teleop_joystick.cpp.

◆ setTaskSpacePathFromPresentPositionOnly() [2/2]

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

◆ setToolControl() [1/2]

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

Definition at line 108 of file open_manipulator_teleop_joystick.cpp.

◆ setToolControl() [2/2]

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

Member Data Documentation

◆ goal_joint_space_path_client_

ros::ServiceClient OpenManipulatorTeleop::goal_joint_space_path_client_
private

Definition at line 75 of file open_manipulator_teleop_joystick.h.

◆ goal_joint_space_path_from_present_client_

ros::ServiceClient OpenManipulatorTeleop::goal_joint_space_path_from_present_client_
private

Definition at line 77 of file open_manipulator_teleop_keyboard.h.

◆ goal_task_space_path_from_present_position_only_client_

ros::ServiceClient OpenManipulatorTeleop::goal_task_space_path_from_present_position_only_client_
private

Definition at line 76 of file open_manipulator_teleop_joystick.h.

◆ goal_tool_control_client_

ros::ServiceClient OpenManipulatorTeleop::goal_tool_control_client_
private

Definition at line 77 of file open_manipulator_teleop_joystick.h.

◆ joint_states_sub_

ros::Subscriber OpenManipulatorTeleop::joint_states_sub_
private

Definition at line 64 of file open_manipulator_teleop_joystick.h.

◆ joy_command_sub_

ros::Subscriber OpenManipulatorTeleop::joy_command_sub_
private

Definition at line 66 of file open_manipulator_teleop_joystick.h.

◆ kinematics_pose_sub_

ros::Subscriber OpenManipulatorTeleop::kinematics_pose_sub_
private

Definition at line 65 of file open_manipulator_teleop_joystick.h.

◆ node_handle_

ros::NodeHandle OpenManipulatorTeleop::node_handle_
private

Definition at line 46 of file open_manipulator_teleop_joystick.h.

◆ oldt_

struct termios OpenManipulatorTeleop::oldt_
private

Definition at line 89 of file open_manipulator_teleop_keyboard.h.

◆ present_joint_angle_

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

Definition at line 58 of file open_manipulator_teleop_joystick.h.

◆ present_kinematic_position_

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

Definition at line 59 of file open_manipulator_teleop_joystick.h.

◆ priv_node_handle_

ros::NodeHandle OpenManipulatorTeleop::priv_node_handle_
private

Definition at line 47 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 Feb 28 2022 23:02:22