HLR  0.0.1
Public Types | Public Member Functions | Static Public Member Functions | List of all members
HLR::Kinematics::Kinematics Class Reference

Contains the functions to compute the forward and inverse kinematics for the mitsubishi rv-2aj robot arm. More...

#include <Kinematics.hpp>

Collaboration diagram for HLR::Kinematics::Kinematics:

Public Types

using IKSolution = std::pair< std::optional< Matrix< double, 4, 1 >>, std::optional< Matrix< double, 4, 1 >>>
 Alias std::pair to IKSolution.
 

Public Member Functions

 Kinematics ()=delete
 Object is not constructable so default constructor is deleted.
 
 ~Kinematics ()=default
 Default destructor.
 
 Kinematics (const Kinematics &k)=delete
 Object is not constructable so copy constructor is deleted. More...
 
 Kinematics (Kinematics &&k)=delete
 Object is not constructable so move constructor is deleted. More...
 
Kinematicsoperator= (const Kinematics &k)=delete
 Object is not constructable so copy assignment is deleted. More...
 
Kinematicsoperator= (Kinematics &&k)=delete
 Object is not constructable so move assignment is deleted. More...
 

Static Public Member Functions

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...
 

Detailed Description

Contains the functions to compute the forward and inverse kinematics for the mitsubishi rv-2aj robot arm.

Constructor & Destructor Documentation

HLR::Kinematics::Kinematics::Kinematics ( const Kinematics k)
delete

Object is not constructable so copy constructor is deleted.

Parameters
k
HLR::Kinematics::Kinematics::Kinematics ( Kinematics &&  k)
delete

Object is not constructable so move constructor is deleted.

Parameters
k

Member Function Documentation

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
goalThe goal to reach.
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
anglesThe 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_anglesThe current angles of each servo.
goalThe goal to reach.
Returns
matrix containing the servo position of each servo. if optional is not filled out it is an unreachable position.
Kinematics& HLR::Kinematics::Kinematics::operator= ( const Kinematics k)
delete

Object is not constructable so copy assignment is deleted.

Parameters
k
Returns
Kinematics& HLR::Kinematics::Kinematics::operator= ( Kinematics &&  k)
delete

Object is not constructable so move assignment is deleted.

Parameters
k
Returns

The documentation for this class was generated from the following file: