open_manipulator_p_teleop_keyboard.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2019 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Darby Lim, Hye-Jong KIM, Ryan Shim, Yong-Ho Na */
18 
19 #ifndef OPEN_MANIPULATOR_P_TELEOP_KEYBOARD_H_
20 #define OPEN_MANIPULATOR_P_TELEOP_KEYBOARD_H_
21 
22 #include <termios.h>
23 
24 #include <ros/ros.h>
25 #include <sensor_msgs/JointState.h>
26 
27 #include "open_manipulator_msgs/SetJointPosition.h"
28 #include "open_manipulator_msgs/SetKinematicsPose.h"
29 
30 #define PI 3.141592
31 #define NUM_OF_JOINT 6
32 #define DELTA 0.01
33 #define JOINT_DELTA 0.05
34 #define PATH_TIME 0.5
35 
37 {
38  public:
41 
42  // update
43  void printText();
44  void setGoal(char ch);
45 
46  private:
47  /*****************************************************************************
48  ** ROS NodeHandle
49  *****************************************************************************/
52 
53  /*****************************************************************************
54  ** ROS Parameters
55  *****************************************************************************/
56  bool with_gripper_;
57 
58  /*****************************************************************************
59  ** Variables
60  *****************************************************************************/
61  std::vector<double> present_joint_angle_;
62  std::vector<double> present_kinematic_position_;
63 
64  /*****************************************************************************
65  ** Init Functions
66  *****************************************************************************/
67  void initSubscriber();
68  void initClient();
69 
70  /*****************************************************************************
71  ** ROS Subscribers, Callback Functions and Relevant Functions
72  *****************************************************************************/
75 
76  void jointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg);
77  void kinematicsPoseCallback(const open_manipulator_msgs::KinematicsPose::ConstPtr &msg);
78 
79  /*****************************************************************************
80  ** ROS Clients and Callback Functions
81  *****************************************************************************/
86 
87  bool setJointSpacePathFromPresent(std::vector<std::string> joint_name, std::vector<double> joint_angle, double path_time);
88  bool setJointSpacePath(std::vector<std::string> joint_name, std::vector<double> joint_angle, double path_time);
89  bool setTaskSpacePathFromPresentPositionOnly(std::vector<double> kinematics_pose, double path_time);
90  bool setToolControl(std::vector<double> joint_angle);
91 
92  /*****************************************************************************
93  ** Others
94  *****************************************************************************/
95  struct termios oldt_;
96 
97  void restoreTerminalSettings(void);
98  void disableWaitingForEnter(void);
99  std::vector<double> getPresentJointAngle();
100  std::vector<double> getPresentKinematicsPose();
101 };
102 
103 #endif //OPEN_MANIPULATOR_P_TELEOP_KEYBOARD_H_
std::vector< double > getPresentKinematicsPose()
void jointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg)
std::vector< double > getPresentJointAngle()
ros::ServiceClient goal_joint_space_path_from_present_client_
bool setTaskSpacePathFromPresentPositionOnly(std::vector< double > kinematics_pose, double path_time)
void kinematicsPoseCallback(const open_manipulator_msgs::KinematicsPose::ConstPtr &msg)
bool setJointSpacePath(std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
std::vector< double > present_kinematic_position_
bool setJointSpacePathFromPresent(std::vector< std::string > joint_name, std::vector< double > joint_angle, double path_time)
ros::ServiceClient goal_task_space_path_from_present_position_only_client_
bool setToolControl(std::vector< double > joint_angle)


open_manipulator_p_teleop
Author(s): Ryan Shim , Yong-Ho Na , Hye-Jong KIM
autogenerated on Thu Oct 22 2020 03:16:41