Endorob  1.4
A C++ Robotics library by P. Berthet-Rayne
hello_world.cpp
Go to the documentation of this file.
1 /*MIT License
2 
3 Copyright (c) 2018-2019 Pierre Berthet-Rayne
4 
5 Permission is hereby granted, free of charge, to any person obtaining a copy
6 of this software and associated documentation files (the "Software"), to deal
7 in the Software without restriction, including without limitation the rights
8 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 copies of the Software, and to permit persons to whom the Software is
10 furnished to do so, subject to the following conditions:
11 
12 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
13 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
14 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
15 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
16 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
17 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
18 SOFTWARE.*/
19 
23 // TO USE THIS LIBRARY, SIMPLY ADD endorob.pri to your Qt creator project
24 
25 #include <QCoreApplication>
26 #include "endorob.h"
27 #include <iostream>
28 
29 int main(int argc, char *argv[])
30 {
31  QCoreApplication app(argc, argv);
32 
33  // Create a Endorob object.
34  Endorob robot;
35 
36  // Set the desired DH convention (optional). The default is modified DH
38 
39  double a = 0.1, alpha = 0, d = 0.01, theta = 0, a_bis = 0;
40 
41  // Fill in the DH table like this (whether you have, prismatic, revolute or rolling joints).
42  robot.add_DH_entry(a,alpha,d,theta, Joint_type::Prismatic);
43  robot.set_joint_limits(-0.1,0.1); // meters for prismatic joints
44  robot.add_DH_entry(a,alpha,d,theta, Joint_type::Revolute);
45  robot.set_joint_limits(-M_PI,M_PI); // radians for revolute or rolling joints
46  robot.add_DH_entry(a,alpha,d,theta, Joint_type::Rolling,a_bis);
47  robot.set_joint_limits(-M_PI/2,M_PI/2); // radians for revolute or rolling joints
48 
49  // Set base frame (optional: for standard DH convention only)
50  Mat4d base;
51  base << 1,0,0,0,
52  0,1,0,0,
53  0,0,1,0,
54  0,0,0,1;
55  robot.set_base_frame(base);
56 
57  // Set tool frame (optional, remember translation first, then rotation)
58  Mat4d tool;
59  tool << 1,0,0,0,
60  0,1,0,0,
61  0,0,1,0,
62  0,0,0,1;
63  robot.set_tool_frame(tool);
64 
65  // Set joint coupling matrix (optional). Must match the size of your DOF
66  Vec coupling(3);
67  coupling << 0, 1, 2;
68  //robot.set_joint_coupling(coupling);
69 
70  // Set mask matrix to reduce workspace dimension (optional)
71  // position, orientation
72  // x, y, z, alpha, beta, gamma
73  Vec mask(6);
74  mask << 1, 1, 1, 0, 0, 0;
75  //robot.set_mask(mask);
76 
77  // Set solver type (optional, default is simple pseudo inverse)
79 
80  // Start solver and thread
81  // Do not forget this line
82  robot.initialize();
83 
84  // Get tip pose:
85  Mat4d Td = robot.get_tip_pose();
86 
87  // Set target for solver:
88  robot.set_solver_target(Td);
89 
90  // Get solver solution (wait for convergence, best function to use, can run real-time)
91  Vec q = robot.get_IK_solution();
92 
93  // Get solver solution (instant solution state, does not guarantee the solution is valid but very fast!)
94  q = robot.get_instant_IK_solution();
95 
96  // Set robot joint vector
97  Vec q_set(robot.dof());
98  q_set << 0.1, 0.4, -0.3, 0.1;
99  robot.set_q_vec(q_set);
100 
101  // Get Jacobian matrix
102  Mat J = robot.get_Jacobian();
103 }
Endorob::set_DH_convention
void set_DH_convention(const DH_type &convention)
Set DH convention: modified or standard.
Definition: endorob.cpp:153
Vec
Eigen::VectorXd Vec
Definition: endorob.h:165
Endorob::add_DH_entry
void add_DH_entry(const double &a, const double &alpha, const double &d, const double &theta, const Joint_type &type, const double &a_bis=0, const double &theta_bis=0, const uint &flex=0)
Setup robot DH table one entry at a time (Attention, modified DH convention by default)
Definition: endorob.cpp:283
Joint_type::Rolling
Rolling-joint (two circular surfaces rolling against each other, changing the contact point)
endorob.h
M_PI
#define M_PI
Definition: endorob.h:131
Endorob::get_IK_solution
Vec get_IK_solution()
Request for solver's converged solution, whether target is reached or not.
Definition: endorob.cpp:1890
Endorob::get_Jacobian
Mat get_Jacobian()
Get the Jacobian matrix of the robot in the current configuration.
Definition: endorob.cpp:654
Endorob
This is the main Class: EndoRob that you can use to control your own weird looking robot....
Definition: endorob.h:420
Joint_type::Prismatic
Standard prismatic joint.
Endorob::set_solver_type
void set_solver_type(Solver_type solver, const double &lambda=1)
Set iterative solver type.
Definition: endorob.cpp:342
Endorob::set_q_vec
void set_q_vec(const Vec &q)
Set robot's joint vector.
Definition: endorob.cpp:1906
Mat
Eigen::MatrixXd Mat
Definition: endorob.h:160
DH_modified
Modified DH approach (better than standard!)
Definition: endorob.h:333
Endorob::initialize
void initialize()
Once all parameters set, initialize robot and start solver.
Definition: endorob.cpp:368
Endorob::dof
unsigned dof()
Get robot number of DOF (different to the number of joints if coupling is used)
Definition: endorob.cpp:551
Endorob::set_joint_limits
void set_joint_limits(const double &min, const double &max)
Set joint limits for current joint, radians for revolute or rolling joints, meters for prismatic.
Definition: endorob.cpp:320
Endorob::set_solver_target
void set_solver_target(const Mat4d &T)
Set solver's target 4x4 homegenous matrix.
Definition: endorob.cpp:2159
Endorob::set_base_frame
void set_base_frame(const Mat4d &T)
Set base frame.
Definition: endorob.cpp:670
Endorob::get_instant_IK_solution
Vec get_instant_IK_solution()
Request for solver's current solution,if solver is still running, the solution may not be valid.
Definition: endorob.cpp:1849
main
int main(int argc, char *argv[])
Definition: hello_world.cpp:29
Mat4d
Eigen::Matrix4d Mat4d
Definition: endorob.h:161
Solver_type::Jacobian_DLS
Damped least square approach.
Endorob::get_tip_pose
Mat4d get_tip_pose()
Get the tip pose / homogeneous matrix (forward kinematics)
Definition: endorob.cpp:952
Endorob::set_tool_frame
void set_tool_frame(const Mat4d &T)
Set tool frame.
Definition: endorob.cpp:665
Joint_type::Revolute
Standard revolute joint.