Barebones Static CTR Library 2.1.4
Loading...
Searching...
No Matches
CTR Class Reference

Class implementing a three-tube Concentric Tube Robot (CTR). More...

#include <CTR.hpp>

Collaboration diagram for CTR:
Collaboration graph

Public Member Functions

 CTR ()=delete
 Removes the default CTR Class constructor.
 
 CTR (const std::array< std::shared_ptr< Tube >, 3UL > &Tb, blaze::StaticVector< double, 6UL > &q, const double Tol, const mathOp::rootFindingMethod method)
 Implements the overloaded constructor for the CTR class.
 
 CTR (const CTR &rhs)
 Implements the copy constructor for the CTR class.
 
 CTR (CTR &&rhs) noexcept
 Implements the move constructor for the CTR class.
 
 ~CTR ()=default
 Destroys the CTR object.
 
CTRoperator= (const CTR &rhs)
 Implements the copy assignment operator for the CTR class.
 
CTRoperator= (CTR &&rhs) noexcept
 Implements the move assignment operator for the CTR class.
 
void reset (const blaze::StaticVector< double, 5UL > &initGuess)
 Resets the std::vector containing all state variables for the CTR at each arc-length.
 
blaze::StaticVector< double, 5UL > ODESolver (const blaze::StaticVector< double, 5UL > &initGuess)
 Solves the CTR model equations (system of ODEs) by numerical integration.
 
blaze::StaticMatrix< double, 5UL, 5UL > jac_BVP (const blaze::StaticVector< double, 5UL > &initGuess, const blaze::StaticVector< double, 5UL > &residue)
 Computes the finite-differences Jacobian for solving the associated Boundary Value Problem (BVP)
 
blaze::StaticMatrix< double, 3UL, 6UL > jacobian (const blaze::StaticVector< double, 5UL > &initGuess, const blaze::StaticVector< double, 3UL > &tipPos)
 Computes the finite-differences Jacobian for the spatial velocities at the distal-end of the CTR.
 
bool PowellDogLeg (blaze::StaticVector< double, 5UL > &initGuess)
 Nonlinear root-finding algorithm for solving the shooting method. It implements the Powell's Dog Leg Method to find the zero of the residue function.
 
bool Levenberg_Marquardt (blaze::StaticVector< double, 5UL > &initGuess)
 Nonlinear root-finding algorithm for solving the shooting method. It implements the Levenberg-Marquardt Method to find the zero of the residue function.
 
bool Broyden (blaze::StaticVector< double, 5UL > &initGuess)
 Nonlinear root-finding algorithm for solving the shooting method. It implements the Broyden's Method (Jacobian inverse is estimated) to find the zero of the residue function.
 
bool Broyden_II (blaze::StaticVector< double, 5UL > &initGuess)
 Nonlinear root-finding algorithm for solving the shooting method. It implements the Broyden's Method (Jacobian inverse is estimated) to find the zero of the residue function.
 
bool Newton_Raphson (blaze::StaticVector< double, 5UL > &initGuess)
 Nonlinear root-finding algorithm for solving the shooting method. It implements the Newton-Raphson's Method to find the zero of the residue function.
 
bool Modified_Newton_Raphson (blaze::StaticVector< double, 5UL > &initGuess)
 Nonlinear root-finding algorithm for solving the shooting method. It implements the modified Newton-Raphson's Method to find the zero of the residue function.
 
bool actuate_CTR (blaze::StaticVector< double, 5UL > &initGuess, const blaze::StaticVector< double, 6UL > &q_input)
 Actuates the CTR robot to a configuration determined by the actuation inputs and the associated boundary conditions dictated by the initial guess for the BVP.
 
bool posCTRL (blaze::StaticVector< double, 5UL > &initGuess, const blaze::StaticVector< double, 3UL > &target, const double Tol)
 Implements the differential inverse kinematics based on resolved rates motion of the actuators.
 
std::array< std::shared_ptr< Tube >, 3UL > getTubes ()
 Returns an std container with smart pointers to the Tube objects comprising the CTR.
 
blaze::StaticVector< double, 3UL > getBeta ()
 Returns the current actuation values of the linear joints of the CTR.
 
blaze::StaticVector< double, 6UL > getConfiguration ()
 Returns the current actuation values of all the linear and revolute joints of the CTR.
 
blaze::StaticVector< double, 3UL > getTipPos ()
 Returns the current end-effector (distal-end) position of the CTR in meters.
 
blaze::StaticVector< double, 3UL > getDistalEnds ()
 Returns the arc-lenghts of each tube's distal end in meters.
 
std::tuple< blaze::HybridMatrix< double, 3UL, 1000UL, blaze::columnMajor >, blaze::HybridMatrix< double, 3UL, 1000UL, blaze::columnMajor >, blaze::HybridMatrix< double, 3UL, 1000UL, blaze::columnMajor > > getTubeShapes ()
 Implements a getter moethod for acquiring the 3-dimensional shape of each tube in the CTR assembly.
 
std::tuple< std::vector< double >, std::vector< double >, std::vector< double > > getShape ()
 Returns a tuple with three std vectors containing the shape of the innermost tube in the CTR assembly.
 
void setConfiguration (const blaze::StaticVector< double, 6UL > &q)
 Implements a setter method for setting the actuation joint values. It does not actuate the CTR (does not solve the FK of the CTR)
 
void setBVPMethod (mathOp::rootFindingMethod mthd)
 Implements a setter method for chosing wich nonlinear root finding algorithm to use when solving the Boundary Value Problem (BVP)
 
void setDistalMoment (const blaze::StaticVector< double, 3UL > &moment)
 Implements a setter method for specifying the point moment acting at the distal-end of the CTR.
 
void setDistalForce (const blaze::StaticVector< double, 3UL > &force)
 Implements a setter method for specifying the point force acting at the distal-end of the CTR.
 

Private Attributes

double m_accuracy
 Defines the accuracy of the numerical solution for the CTR Boundary Value Problem (BVP).
 
mathOp::rootFindingMethod m_method
 Available root-finding methods: Newton-Raphson, Levenberg-Marquardt, Powell (dog-leg), Broyden.
 
std::array< std::shared_ptr< Tube >, 3UL > m_Tubes
 Array of smart pointers to the Tube objects comprising the CTR.
 
blaze::StaticVector< double, 3UL > m_beta
 Linear actuation values [beta_1, beta_2, beta_3].
 
blaze::StaticVector< double, 6UL > m_q
 Joint actuation values [alpha_1, alpha_2, alpha_3].
 
blaze::StaticVector< double, 3UL > m_theta_0
 Initial twist angle for all tubes at s = 0.
 
blaze::StaticVector< double, 4UL > m_h_0
 Initial orientation of the local frame at s = 0, represented as a quaternion.
 
blaze::StaticVector< double, 3UL > m_wf
 External point force at the distal-end of the CTR (force component of the external wrench).
 
blaze::StaticVector< double, 3UL > m_wm
 External point moment at the distal-end of the CTR (moment component of the external wrench).
 
blaze::StaticVector< double, 3UL > m_e3
 Third canonical basis of R^3.
 
std::unique_ptr< Segmentm_segment
 Unique pointer to the segments between transition points along the CTR backbone.
 
std::vector< state_type > m_y
 Stores the CTR state vector at each arc-length (spatial integration step).
 
std::vector< double > m_s
 Stores the discrete arc-length points (in meters) along the backbone.
 
std::unique_ptr< ODESystemm_stateEquations
 Unique pointer to the ODE system implementing the state differential equations for a three-tube CTR.
 
std::unique_ptr< Observerm_stateObserver
 Unique pointer to the state observer for Boost::odeInt.
 

Detailed Description

Class implementing a three-tube Concentric Tube Robot (CTR).

Constructor & Destructor Documentation

◆ CTR() [1/3]

CTR::CTR ( const std::array< std::shared_ptr< Tube >, 3UL > & Tb,
blaze::StaticVector< double, 6UL > & q,
const double Tol,
const mathOp::rootFindingMethod method )

Implements the overloaded constructor for the CTR class.

Parameters
TbA 3-dimensional std::array containing smart pointers to the three tube objects comprising the CTR assembly.
qA 6-dimensional static Blaze vector containing the actuation input values for the CTR.
TolA scalar that dictates the prescribed accuracy (tolerance) for solving the associated Boundary Value Problem (BVP).
methodAn enum class specifying the root-finding method. The possible choices are: NEWTON_RAPHSON, LEVENBERG_MARQUARDT, POWELL_DOG_LEG, MODIFIED_NEWTON_RAPHSON, BROYDEN, and BROYDEN_II.

◆ CTR() [2/3]

CTR::CTR ( const CTR & rhs)

Implements the copy constructor for the CTR class.

Parameters
rhsThe source CTR object to copy from.

◆ CTR() [3/3]

CTR::CTR ( CTR && rhs)
noexcept

Implements the move constructor for the CTR class.

Parameters
rhsThe source CTR object to move from.

Member Function Documentation

◆ actuate_CTR()

bool CTR::actuate_CTR ( blaze::StaticVector< double, 5UL > & initGuess,
const blaze::StaticVector< double, 6UL > & q_input )

Actuates the CTR robot to a configuration determined by the actuation inputs and the associated boundary conditions dictated by the initial guess for the BVP.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
q_inputis a 6-dimensional vector of the actuation units The first three entries are the linear joints, the last three are the revolute ones.
Returns
a boolean flag. True: the associated BVP has been solved successfully | False: otherwise

◆ Broyden()

bool CTR::Broyden ( blaze::StaticVector< double, 5UL > & initGuess)

Nonlinear root-finding algorithm for solving the shooting method. It implements the Broyden's Method (Jacobian inverse is estimated) to find the zero of the residue function.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
Returns
a boolean flag. True: the zero (root) of the residue function has been found | False: the zero (root) of the residue function has not been found

◆ Broyden_II()

bool CTR::Broyden_II ( blaze::StaticVector< double, 5UL > & initGuess)

Nonlinear root-finding algorithm for solving the shooting method. It implements the Broyden's Method (Jacobian inverse is estimated) to find the zero of the residue function.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
Returns
a boolean flag. True: the zero (root) of the residue function has been found | False: the zero (root) of the residue function has not been found

◆ getBeta()

blaze::StaticVector< double, 3UL > CTR::getBeta ( )

Returns the current actuation values of the linear joints of the CTR.

Returns
a static 3-dimensional Blaze vector with the actuation values for the linear joints [beta_1, beta_2, beta_3]

◆ getConfiguration()

blaze::StaticVector< double, 6UL > CTR::getConfiguration ( )

Returns the current actuation values of all the linear and revolute joints of the CTR.

Returns
a static Blaze vector with the actuation values for all the joints [beta_1, beta_2, beta_3, alpha_1, alpha_2, alpha_3]

◆ getDistalEnds()

blaze::StaticVector< double, 3UL > CTR::getDistalEnds ( )

Returns the arc-lenghts of each tube's distal end in meters.

Returns
a static 3-dimensional Blaze vector with the arc-length distal-end positions of each tube in the CTR assembly

◆ getShape()

std::tuple< std::vector< double >, std::vector< double >, std::vector< double > > CTR::getShape ( )

Returns a tuple with three std vectors containing the shape of the innermost tube in the CTR assembly.

Returns
a tuple with the set of three std::vectors with the shape of the innermost tube in the CTR assembly. The first, second, and third entries in the tuple correspond to the x,y,z coordinates of the tube centerline

◆ getTipPos()

blaze::StaticVector< double, 3UL > CTR::getTipPos ( )

Returns the current end-effector (distal-end) position of the CTR in meters.

Returns
a static 3-dimensional Blaze vector with the position of the distal-end of the CTR

◆ getTubes()

std::array< std::shared_ptr< Tube >, 3UL > CTR::getTubes ( )

Returns an std container with smart pointers to the Tube objects comprising the CTR.

Returns
smart pointers to the tubes comprising the CTR assembly

◆ getTubeShapes()

std::tuple< blaze::HybridMatrix< double, 3UL, 1000UL, blaze::columnMajor >, blaze::HybridMatrix< double, 3UL, 1000UL, blaze::columnMajor >, blaze::HybridMatrix< double, 3UL, 1000UL, blaze::columnMajor > > CTR::getTubeShapes ( )

Implements a getter moethod for acquiring the 3-dimensional shape of each tube in the CTR assembly.

Returns
a set of three 3xN Blaze matrices with the shape of each tube in the CTR assembly. The first, second, and third rows of each matrix correspond to the x,y,z coordinates

◆ jac_BVP()

blaze::StaticMatrix< double, 5UL, 5UL > CTR::jac_BVP ( const blaze::StaticVector< double, 5UL > & initGuess,
const blaze::StaticVector< double, 5UL > & residue )

Computes the finite-differences Jacobian for solving the associated Boundary Value Problem (BVP)

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
residueis the residue (violation of the distal boundary condition) at the current iteration of the shooting problem.
Returns
a 5x5 BVP Jacobian matrix that relates how the residue changes as a function of the initial guesses

◆ jacobian()

blaze::StaticMatrix< double, 3UL, 6UL > CTR::jacobian ( const blaze::StaticVector< double, 5UL > & initGuess,
const blaze::StaticVector< double, 3UL > & tipPos )

Computes the finite-differences Jacobian for the spatial velocities at the distal-end of the CTR.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
tipPosis the current distal-end position at the current iteration of the inverse kinematics (position control problem).
Returns
a 3x6 BVP Jacobian matrix that relates how the distal spatial velocities residue change as a function of the actuation inputs

◆ Levenberg_Marquardt()

bool CTR::Levenberg_Marquardt ( blaze::StaticVector< double, 5UL > & initGuess)

Nonlinear root-finding algorithm for solving the shooting method. It implements the Levenberg-Marquardt Method to find the zero of the residue function.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
Returns
a boolean flag. True: the zero (root) of the residue function has been found | False: the zero (root) of the residue function has not been found

◆ Modified_Newton_Raphson()

bool CTR::Modified_Newton_Raphson ( blaze::StaticVector< double, 5UL > & initGuess)

Nonlinear root-finding algorithm for solving the shooting method. It implements the modified Newton-Raphson's Method to find the zero of the residue function.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
Returns
a boolean flag. True: the zero (root) of the residue function has been found | False: the zero (root) of the residue function has not been found

◆ Newton_Raphson()

bool CTR::Newton_Raphson ( blaze::StaticVector< double, 5UL > & initGuess)

Nonlinear root-finding algorithm for solving the shooting method. It implements the Newton-Raphson's Method to find the zero of the residue function.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
Returns
a boolean flag. True: the zero (root) of the residue function has been found | False: the zero (root) of the residue function has not been found

◆ ODESolver()

blaze::StaticVector< double, 5UL > CTR::ODESolver ( const blaze::StaticVector< double, 5UL > & initGuess)

Solves the CTR model equations (system of ODEs) by numerical integration.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
Returns
a 5-dimensional residue vector. The residue is the violation of the distal boundary condition

◆ operator=() [1/2]

CTR & CTR::operator= ( const CTR & rhs)

Implements the copy assignment operator for the CTR class.

Parameters
rhsThe source CTR object to copy from.
Returns
A reference to the assigned CTR object.

◆ operator=() [2/2]

CTR & CTR::operator= ( CTR && rhs)
noexcept

Implements the move assignment operator for the CTR class.

Parameters
rhsThe source CTR object to move from.
Returns
A reference to the assigned CTR object.

◆ posCTRL()

bool CTR::posCTRL ( blaze::StaticVector< double, 5UL > & initGuess,
const blaze::StaticVector< double, 3UL > & target,
const double Tol )

Implements the differential inverse kinematics based on resolved rates motion of the actuators.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
targetis a 3-dimensional vector of the target position to where the end-effector (distal-end of the CTR) should be steered to.
Tolis a scalar indicating the tolerance with which the position control problem should be solved.
Returns
a boolean flag. True: the associated IK has been solved successfully within the prescribed tolerance | False: otherwise

◆ PowellDogLeg()

bool CTR::PowellDogLeg ( blaze::StaticVector< double, 5UL > & initGuess)

Nonlinear root-finding algorithm for solving the shooting method. It implements the Powell's Dog Leg Method to find the zero of the residue function.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).
Returns
a boolean flag. True: the zero (root) of the residue function has been found | False: the zero (root) of the residue function has not been found

◆ reset()

void CTR::reset ( const blaze::StaticVector< double, 5UL > & initGuess)

Resets the std::vector containing all state variables for the CTR at each arc-length.

Parameters
initGuessis the initial guess 5-dimensional vector for the boundary value problem (BVP).

◆ setBVPMethod()

void CTR::setBVPMethod ( mathOp::rootFindingMethod mthd)

Implements a setter method for chosing wich nonlinear root finding algorithm to use when solving the Boundary Value Problem (BVP)

Parameters
mthdenum class specifying the root-finding method. The possible choices are: NEWTON_RAPHSON, LEVENBERG_MARQUARDT, POWELL_DOG_LEG, MODIFIED_NEWTON_RAPHSON, BROYDEN, and BROYDEN_II.

◆ setConfiguration()

void CTR::setConfiguration ( const blaze::StaticVector< double, 6UL > & q)

Implements a setter method for setting the actuation joint values. It does not actuate the CTR (does not solve the FK of the CTR)

Parameters
qis a static 6-dimensional Blaze vector containing the actuation values for the CTR joints [beta_1, beta_2, beta_3, alpha_1, alpha_2, alpha_3]

◆ setDistalForce()

void CTR::setDistalForce ( const blaze::StaticVector< double, 3UL > & force)

Implements a setter method for specifying the point force acting at the distal-end of the CTR.

Parameters
forceis a static 3-dimensional Blaze vector containing the point force acting at the distal-end of the CTR.

◆ setDistalMoment()

void CTR::setDistalMoment ( const blaze::StaticVector< double, 3UL > & moment)

Implements a setter method for specifying the point moment acting at the distal-end of the CTR.

Parameters
momentis a static 3-dimensional Blaze vector containing the moment acting at the distal-end of the CTR.

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