Barebones Static CTR Library 2.1.4
|
Class implementing a three-tube Concentric Tube Robot (CTR). More...
#include <CTR.hpp>
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. | |
CTR & | operator= (const CTR &rhs) |
Implements the copy assignment operator for the CTR class. | |
CTR & | operator= (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< Segment > | m_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< ODESystem > | m_stateEquations |
Unique pointer to the ODE system implementing the state differential equations for a three-tube CTR. | |
std::unique_ptr< Observer > | m_stateObserver |
Unique pointer to the state observer for Boost::odeInt. | |
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.
Tb | A 3-dimensional std::array containing smart pointers to the three tube objects comprising the CTR assembly. |
q | A 6-dimensional static Blaze vector containing the actuation input values for the CTR. |
Tol | A scalar that dictates the prescribed accuracy (tolerance) for solving the associated Boundary Value Problem (BVP). |
method | An 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::CTR | ( | const CTR & | rhs | ) |
|
noexcept |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
q_input | is a 6-dimensional vector of the actuation units The first three entries are the linear joints, the last three are the revolute ones. |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
blaze::StaticVector< double, 3UL > CTR::getBeta | ( | ) |
Returns the current actuation values of the linear joints of the CTR.
blaze::StaticVector< double, 6UL > CTR::getConfiguration | ( | ) |
Returns the current actuation values of all the linear and revolute joints of the CTR.
blaze::StaticVector< double, 3UL > CTR::getDistalEnds | ( | ) |
Returns the arc-lenghts of each tube's distal end in meters.
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.
blaze::StaticVector< double, 3UL > CTR::getTipPos | ( | ) |
std::array< std::shared_ptr< Tube >, 3UL > CTR::getTubes | ( | ) |
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 | ( | ) |
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)
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
residue | is the residue (violation of the distal boundary condition) at the current iteration of the shooting problem. |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
tipPos | is the current distal-end position at the current iteration of the inverse kinematics (position control problem). |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
blaze::StaticVector< double, 5UL > CTR::ODESolver | ( | const blaze::StaticVector< double, 5UL > & | initGuess | ) |
Solves the CTR model equations (system of ODEs) by numerical integration.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
target | is a 3-dimensional vector of the target position to where the end-effector (distal-end of the CTR) should be steered to. |
Tol | is a scalar indicating the tolerance with which the position control problem should be solved. |
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.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
void CTR::reset | ( | const blaze::StaticVector< double, 5UL > & | initGuess | ) |
Resets the std::vector containing all state variables for the CTR at each arc-length.
initGuess | is the initial guess 5-dimensional vector for the boundary value problem (BVP). |
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)
mthd | 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. |
void CTR::setConfiguration | ( | const blaze::StaticVector< double, 6UL > & | q | ) |
void CTR::setDistalForce | ( | const blaze::StaticVector< double, 3UL > & | force | ) |
void CTR::setDistalMoment | ( | const blaze::StaticVector< double, 3UL > & | moment | ) |