robotis_manipulator_trajectory_generator.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 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 ROBOTIS_MNAMIPULATOR_TRAJECTORY_GENERATOR_H_
20 #define ROBOTIS_MNAMIPULATOR_TRAJECTORY_GENERATOR_H_
21 
22 #include <math.h>
23 #include <vector>
24 
26 
27 #if defined(__OPENCR__)
28  #include <Eigen.h> // Calls main Eigen matrix class library
29  #include <Eigen/LU> // Calls inverse, determinant, LU decomp., etc.
30  #include <Eigen/QR>
31 #else
32  #include <eigen3/Eigen/Eigen>
33  #include <eigen3/Eigen/LU>
34  #include <eigen3/Eigen/QR>
35 
36  #define PI 3.141592
37 #endif
38 
39 namespace robotis_manipulator
40 {
42 {
43 private:
44  Eigen::VectorXd coefficient_;
45 
46 public:
47  MinimumJerk();
48  virtual ~MinimumJerk();
49 
50  void calcCoefficient(Point start,
51  Point goal,
52  double move_time);
53 
54  Eigen::VectorXd getCoefficient();
55 };
56 
58 {
59 private:
62  Eigen::MatrixXd minimum_jerk_coefficient_;
63 
64 public:
66  virtual ~JointTrajectory();
67 
74  bool makeJointTrajectory(double move_time,
75  JointWaypoint start,
76  JointWaypoint goal
77  );
78  Eigen::MatrixXd getMinimumJerkCoefficient();
79  JointWaypoint getJointWaypoint(double tick);
80 };
81 
83 {
84 private:
87  Eigen::MatrixXd minimum_jerk_coefficient_;
88 
89 public:
91  virtual ~TaskTrajectory();
92 
99  bool makeTaskTrajectory(double move_time,
100  TaskWaypoint start,
101  TaskWaypoint goal
102  );
103  Eigen::MatrixXd getMinimumJerkCoefficient();
104  TaskWaypoint getTaskWaypoint(double tick);
105 };
106 
107 
108 /*****************************************************************************
109 ** Trajectory Class
110 *****************************************************************************/
112 {
113 private:
117 
120  std::map<Name, CustomJointTrajectory *> cus_joint_;
121  std::map<Name, CustomTaskTrajectory *> cus_task_;
122 
125 
126 public:
129 
130  // Time
131  void setMoveTime(double move_time);
132  void setPresentTime(double present_time);
133  void setStartTimeToPresentTime();
134  void setStartTime(double start_time);
135  double getMoveTime();
136  double getTickTime();
137 
138  // Manipulator
139  void setManipulator(Manipulator manipulator);
140  Manipulator* getManipulator();
141 
142  // Get Trajectory
143  JointTrajectory getJointTrajectory();
144  TaskTrajectory getTaskTrajectory();
145  CustomJointTrajectory* getCustomJointTrajectory(Name name);
146  CustomTaskTrajectory* getCustomTaskTrajectory(Name name);
147 
148  // Custom Trajectory Setting
149  void addCustomTrajectory(Name trajectory_name, CustomJointTrajectory *custom_trajectory);
150  void addCustomTrajectory(Name trajectory_name, CustomTaskTrajectory *custom_trajectory);
151  void setCustomTrajectoryOption(Name trajectory_name, const void* arg);
152  void setPresentControlToolName(Name present_control_tool_name);
153  Name getPresentCustomTrajectoryName();
154  Name getPresentControlToolName();
155 
156  // First Waypoint
157  void initTrajectoryWaypoint(Manipulator actual_manipulator, Kinematics *kinematics=nullptr);
158 
159  // Present Waypoint
160  void updatePresentWaypoint(Kinematics* kinematics); //forward kinematics,dynamics
161  void setPresentJointWaypoint(JointWaypoint joint_value_vector);
162  void setPresentTaskWaypoint(Name tool_name, TaskWaypoint tool_position_value_vector);
163  JointWaypoint getPresentJointWaypoint();
164  TaskWaypoint getPresentTaskWaypoint(Name tool_name);
165 
166  JointWaypoint removeWaypointDynamicData(JointWaypoint value);
167  TaskWaypoint removeWaypointDynamicData(TaskWaypoint value);
168 
169  // Trajectory
170  void setTrajectoryType(TrajectoryType trajectory_type);
171  bool checkTrajectoryType(TrajectoryType trajectory_type);
177  bool makeJointTrajectory(JointWaypoint start_way_point, JointWaypoint goal_way_point);
183  bool makeTaskTrajectory(TaskWaypoint start_way_point, TaskWaypoint goal_way_point);
190  bool makeCustomTrajectory(Name trajectory_name, JointWaypoint start_way_point, const void *arg);
197  bool makeCustomTrajectory(Name trajectory_name, TaskWaypoint start_way_point, const void *arg);
198 
199  // Tool
205  bool setToolGoalPosition(Name tool_name, double tool_goal_position);
211  bool setToolGoalValue(Name tool_name, JointValue tool_goal_value);
217  double getToolGoalPosition(Name tool_name);
218  JointValue getToolGoalValue(Name tool_name);
219 };
220 
221 } // namespace robotis_manipulator
222 #endif // ROBOTIS_MNAMIPULATOR_TRAJECTORY_GENERATOR_H_
223 
224 
225 
enum robotis_manipulator::_TrajectoryType TrajectoryType
void calcCoefficient(Point start, Point goal, double move_time)
std::map< Name, CustomTaskTrajectory * > cus_task_
std::vector< JointValue > JointWaypoint
std::map< Name, CustomJointTrajectory * > cus_joint_


robotis_manipulator
Author(s): Hye-Jong KIM , Darby Lim , Yong-Ho Na , Ryan Shim
autogenerated on Sat Oct 3 2020 03:14:51