robotis_manipulator_manager.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_MANIPULATOR_MANAGER_H_
20 #define ROBOTIS_MANIPULATOR_MANAGER_H_
21 
22 #if defined(__OPENCR__)
23  #include <Eigen.h> // Calls main Eigen matrix class library
24 #else
25  #include <eigen3/Eigen/Eigen>
26 #endif
27 
29 
30 namespace robotis_manipulator
31 {
32 
34 {
35 public:
37  virtual ~Kinematics() {}
38 
39  virtual void setOption(const void *arg) = 0;
40  virtual Eigen::MatrixXd jacobian(Manipulator *manipulator, Name tool_name) = 0;
41  virtual void solveForwardKinematics(Manipulator *manipulator) = 0; //Every joint value to every component pose
42  virtual bool solveInverseKinematics(Manipulator *manipulator, Name tool_name, Pose target_pose, std::vector<JointValue>* goal_joint_position) = 0; //An component pose to every joint value
43 };
44 
45 class Dynamics
46 {
47 public:
48  Dynamics() {}
49  virtual ~Dynamics() {}
50 
51  virtual bool setOption(STRING param_name, const void *arg) = 0;
52  virtual bool setEnvironments(STRING param_name, const void *arg) = 0;
53  virtual bool solveForwardDynamics(Manipulator *manipulator, std::map<Name, double> joint_torque) = 0; //torque to joint value
54  virtual bool solveInverseDynamics(Manipulator manipulator, std::map<Name, double>* joint_torque) = 0; //joint values to torque
55 };
56 
57 
59 {
60 public:
62 
63  JointActuator() : enabled_state_(false) {}
64  virtual ~JointActuator() {}
65 
66  virtual void init(std::vector<uint8_t> actuator_id, const void *arg) = 0;
67  virtual void setMode(std::vector<uint8_t> actuator_id, const void *arg) = 0;
68  virtual std::vector<uint8_t> getId() = 0;
69 
70  virtual void enable() = 0;
71  virtual void disable() = 0;
72 
73  virtual bool sendJointActuatorValue(std::vector<uint8_t> actuator_id, std::vector<ActuatorValue> value_vector) = 0;
74  virtual std::vector<ActuatorValue> receiveJointActuatorValue(std::vector<uint8_t> actuator_id) = 0;
75 
76  bool findId(uint8_t actuator_id);
77  bool getEnabledState();
78 };
79 
81 {
82 public:
84 
85  ToolActuator():enabled_state_(false){}
86  virtual ~ToolActuator() {}
87 
88  virtual void init(uint8_t actuator_id, const void *arg) = 0;
89  virtual void setMode(const void *arg) = 0;
90  virtual uint8_t getId() = 0;
91 
92  virtual void enable() = 0;
93  virtual void disable() = 0;
94 
95  virtual bool sendToolActuatorValue(ActuatorValue value) = 0;
96  virtual ActuatorValue receiveToolActuatorValue() = 0;
97 
98  bool findId(uint8_t actuator_id);
99  bool getEnabledState();
100 };
101 
102 
104 {
105 public:
108 
109  virtual void makeJointTrajectory(double move_time, JointWaypoint start, const void *arg) = 0;
110  virtual void setOption(const void *arg) = 0;
111  virtual JointWaypoint getJointWaypoint(double tick) = 0;
112 };
113 
115 {
116 public:
119 
120  virtual void makeTaskTrajectory(double move_time, TaskWaypoint start, const void *arg) = 0;
121  virtual void setOption(const void *arg) = 0;
122  virtual TaskWaypoint getTaskWaypoint(double tick) = 0;
123 };
124 
125 } // namespace ROBOTIS_MANIPULATOR
126 #endif
ROSCPP_DECL void start()
virtual void solveForwardKinematics(Manipulator *manipulator)=0
virtual bool solveInverseKinematics(Manipulator *manipulator, Name tool_name, Pose target_pose, std::vector< JointValue > *goal_joint_position)=0
void init(const M_string &remappings)
virtual Eigen::MatrixXd jacobian(Manipulator *manipulator, Name tool_name)=0
std::vector< JointValue > JointWaypoint
virtual void setOption(const void *arg)=0
std::string STRING


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