open_manipulator_teleop_joystick.h
Go to the documentation of this file.
1 #ifndef OPEN_MANIPULATOR_TELEOP_H
2 #define OPEN_MANIPULATOR_TELEOP_H
3 
4 #include <ros/ros.h>
5 #include <sensor_msgs/JointState.h>
6 #include <sensor_msgs/Joy.h>
7 
8 #include <termios.h>
9 #include "open_manipulator_msgs/SetJointPosition.h"
10 #include "open_manipulator_msgs/SetKinematicsPose.h"
11 
12 #define NUM_OF_JOINT 4
13 #define DELTA 0.01
14 #define JOINT_DELTA 0.05
15 #define PATH_TIME 0.5
16 
18 {
19  private:
20  // ROS NodeHandle
23 
27 
31 
32  std::vector<double> present_joint_angle_;
33  std::vector<double> present_kinematic_position_;
34 
35  public:
36 
39 
40  void initClient();
41  void initSubscriber();
42 
43  void jointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg);
44  void kinematicsPoseCallback(const open_manipulator_msgs::KinematicsPose::ConstPtr &msg);
45  void joyCallback(const sensor_msgs::Joy::ConstPtr &msg);
46 
47  std::vector<double> getPresentJointAngle();
48  std::vector<double> getPresentKinematicsPose();
49 
50  bool setJointSpacePath(std::vector<std::string> joint_name, std::vector<double> joint_angle, double path_time);
51 
52  bool setTaskSpacePathFromPresentPositionOnly(std::vector<double> kinematics_pose, double path_time);
53 
54  bool setToolControl(std::vector<double> joint_angle);
55 
56  void setGoal(const char *str);
57 };
58 
59 #endif //OPEN_MANIPULATOR_TELEOP_H
std::vector< double > getPresentKinematicsPose()
ros::ServiceClient goal_joint_space_path_client_
void jointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg)
std::vector< double > getPresentJointAngle()
bool setTaskSpacePathFromPresentPositionOnly(std::vector< double > kinematics_pose, double path_time)
void kinematicsPoseCallback(const open_manipulator_msgs::KinematicsPose::ConstPtr &msg)
std::vector< double > present_joint_angle_
bool setJointSpacePath(std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
std::vector< double > present_kinematic_position_
ros::ServiceClient goal_task_space_path_from_present_position_only_client_
void joyCallback(const sensor_msgs::Joy::ConstPtr &msg)
bool setToolControl(std::vector< double > joint_angle)


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