ur_kin.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Provides forward and inverse kinematics for Univeral robot designs
4  * Author: Kelsey Hawkins (kphawkins@gatech.edu)
5  *
6  * Software License Agreement (BSD License)
7  *
8  * Copyright (c) 2013, Georgia Institute of Technology
9  * All rights reserved.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of the Georgia Institute of Technology nor the names of
22  * its contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *********************************************************************/
38 #ifndef UR_KIN_H
39 #define UR_KIN_H
40 
41 // These kinematics find the tranfrom from the base link to the end effector.
42 // Though the raw D-H parameters specify a transform from the 0th link to the 6th link,
43 // offset transforms are specified in this formulation.
44 // To work with the raw D-H kinematics, use the inverses of the transforms below.
45 
46 // Transform from base link to 0th link
47 // -1, 0, 0, 0
48 // 0, -1, 0, 0
49 // 0, 0, 1, 0
50 // 0, 0, 0, 1
51 
52 // Transform from 6th link to end effector
53 // 0, -1, 0, 0
54 // 0, 0, -1, 0
55 // 1, 0, 0, 0
56 // 0, 0, 0, 1
57 
58 namespace ur_kinematics {
59  // @param q The 6 joint values
60  // @param T The 4x4 end effector pose in row-major ordering
61  void forward(const double* q, double* T);
62 
63  // @param q The 6 joint values
64  // @param Ti The 4x4 link i pose in row-major ordering. If NULL, nothing is stored.
65  void forward_all(const double* q, double* T1, double* T2, double* T3,
66  double* T4, double* T5, double* T6);
67 
68  // @param T The 4x4 end effector pose in row-major ordering
69  // @param q_sols An 8x6 array of doubles returned, all angles should be in [0,2*PI)
70  // @param q6_des An optional parameter which designates what the q6 value should take
71  // in case of an infinite solution on that joint.
72  // @return Number of solutions found (maximum of 8)
73  int inverse(const double* T, double* q_sols, double q6_des=0.0);
74 };
75 
76 #endif //UR_KIN_H
int inverse(const double *T, double *q_sols, double q6_des=0.0)
Definition: ur_kin.cpp:197
void forward_all(const double *q, double *T1, double *T2, double *T3, double *T4, double *T5, double *T6)
Definition: ur_kin.cpp:71
void forward(const double *q, double *T)
Definition: ur_kin.cpp:47


ur_kinematics
Author(s): Kelsey Hawkins
autogenerated on Sun Nov 24 2019 03:36:27