Contains the functions to compute the forward and inverse kinematics for the mitsubishi rv-2aj robot arm.
More...
#include <Kinematics.hpp>
|
using | IKSolution = std::pair< std::optional< Matrix< double, 4, 1 >>, std::optional< Matrix< double, 4, 1 >>> |
| Alias std::pair to IKSolution.
|
|
|
static std::optional< Matrix< double, 3, 4 > > | forward (Matrix< double, 4, 1 > angles) |
| Calculate forward kinematics given the angles of the robot arm. More...
|
|
static IKSolution | jacobian_inverse (Matrix< double, 4, 1 > current_angles, const Matrix< double, 3, 1 > &goal) |
| Calculate joint angles based on the position the end effector of the robot arm should have. This will use the inverse jacobian numerical method. More...
|
|
static IKSolution | analytical_inverse (const Matrix< double, 3, 1 > &goal) |
| Calculate joint angles based on the position the end effector of the robot arm should have. This will use the analytical solution, and can return two solutions. More...
|
|
Contains the functions to compute the forward and inverse kinematics for the mitsubishi rv-2aj robot arm.
HLR::Kinematics::Kinematics::Kinematics |
( |
const Kinematics & |
k | ) |
|
|
delete |
Object is not constructable so copy constructor is deleted.
- Parameters
-
HLR::Kinematics::Kinematics::Kinematics |
( |
Kinematics && |
k | ) |
|
|
delete |
Object is not constructable so move constructor is deleted.
- Parameters
-
static IKSolution HLR::Kinematics::Kinematics::analytical_inverse |
( |
const Matrix< double, 3, 1 > & |
goal | ) |
|
|
static |
Calculate joint angles based on the position the end effector of the robot arm should have. This will use the analytical solution, and can return two solutions.
- Parameters
-
- Returns
- pair of matrices containing the servo position of each servo. if both optionals iare not filled out it is an unreachable position.
static std::optional<Matrix<double, 3, 4> > HLR::Kinematics::Kinematics::forward |
( |
Matrix< double, 4, 1 > |
angles | ) |
|
|
static |
Calculate forward kinematics given the angles of the robot arm.
- Parameters
-
angles | The angles of each joint. |
- Returns
- The position of each joint starting from base. Where it's in the format x, y, z. So the last row in the matrix contains the end effector position. If it can't be calculated due to servo limitations the optional is empty.
static IKSolution HLR::Kinematics::Kinematics::jacobian_inverse |
( |
Matrix< double, 4, 1 > |
current_angles, |
|
|
const Matrix< double, 3, 1 > & |
goal |
|
) |
| |
|
static |
Calculate joint angles based on the position the end effector of the robot arm should have. This will use the inverse jacobian numerical method.
- Parameters
-
current_angles | The current angles of each servo. |
goal | The goal to reach. |
- Returns
- matrix containing the servo position of each servo. if optional is not filled out it is an unreachable position.
Object is not constructable so copy assignment is deleted.
- Parameters
-
- Returns
Object is not constructable so move assignment is deleted.
- Parameters
-
- Returns
The documentation for this class was generated from the following file: