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

Class representing Segments between transition points in a Concentric Tube Robot (CTR). More...

#include <Segment.hpp>

Collaboration diagram for Segment:
Collaboration graph

Public Member Functions

 Segment ()
 Implements the default constructor for the Segment class.
 
 Segment (const std::array< std::shared_ptr< Tube >, 3UL > &Tb, const blaze::StaticVector< double, 3UL > &beta)
 Implements the overloaded constructor for the Segment class.
 
 Segment (const Segment &rhs)
 Implements the copy constructor for the Segment class.
 
 Segment (Segment &&rhs) noexcept
 Implements the move constructor for the Segment class.
 
 ~Segment ()=default
 Destroys the Segment object.
 
Segmentoperator= (const Segment &rhs)
 Implements the copy assignment operator for the Segment class.
 
Segmentoperator= (Segment &&rhs) noexcept
 Implements the move assignment operator for the Segment class.
 
void recalculateSegments (const std::array< std::shared_ptr< Tube >, 3UL > &Tb, const blaze::StaticVector< double, 3UL > &beta)
 Computes the tube transition points and the corresponding parameters at each segment.
 
const std::vector< double > & get_S () const
 Implements a getter method for retrieving all the transition points currently present in the CTR assembly.
 
const blaze::StaticVector< double, 3UL > & getDistalEnds () const
 Implements a getter method for retrieving the distal ends of all tubes in the CTR assembly.
 
const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > & get_EI () const
 Implements a getter method for retrieving the bending stiffness of the tubes in all of the tube segments in the CTR assembly.
 
const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > & get_GJ () const
 Implements a getter method for retrieving the torsional stiffness of the tubes in all of the tube segments in the CTR assembly.
 
const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > & get_U_x () const
 Implements a getter method for retrieving the pre-curvature of the tubes along the 'x' direction in all of the tube segments in the CTR assembly.
 
const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > & get_U_y () const
 Implements a getter method for retrieving the pre-curvature of the tubes along the 'y' direction in all of the tube segments in the CTR assembly.
 
std::tuple< const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > &, const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > &, const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > &, const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > &, const std::vector< double > & > returnParameters () const
 Implements a getter method for retrieving all parameters along all segments in the CTR assembly.
 

Private Attributes

std::vector< double > m_S
 Arc-length of each tube transition point.
 
blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > m_EI
 Tubes' bending stiffness – x, y directions.
 
blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > m_GJ
 Tubes' torsional stiffness – z direction.
 
blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > m_U_x
 Tubes' precurvature in the x direction.
 
blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > m_U_y
 Tubes' precurvature in the y direction.
 
blaze::StaticVector< double, 3UL > m_len_curv
 Arc-length at which precurvature starts in the tubes.
 
blaze::StaticVector< double, 3UL > m_dist_end
 Arc-length at which the tubes terminate (distal-ends).
 

Detailed Description

Class representing Segments between transition points in a Concentric Tube Robot (CTR).

Constructor & Destructor Documentation

◆ Segment() [1/3]

Segment::Segment ( const std::array< std::shared_ptr< Tube >, 3UL > & Tb,
const blaze::StaticVector< double, 3UL > & beta )

Implements the overloaded constructor for the Segment class.

Parameters
TbA 3-dimensional std::array containing smart pointers to the three tube objects comprising the CTR assembly.
betaA 3-dimensional static Blaze vector containing the actuation input values for the linear joints of the CTR.

◆ Segment() [2/3]

Segment::Segment ( const Segment & rhs)

Implements the copy constructor for the Segment class.

Parameters
rhsThe source Segment object to copy from.

◆ Segment() [3/3]

Segment::Segment ( Segment && rhs)
noexcept

Implements the move constructor for the Segment class.

Parameters
rhsThe source Segment object to move from.

Member Function Documentation

◆ get_EI()

const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > & Segment::get_EI ( ) const

Implements a getter method for retrieving the bending stiffness of the tubes in all of the tube segments in the CTR assembly.

Returns
A 3xN hybrid Blaze matrix containing the bending stiffness [k_x, k_y, 0] for the tube assembly between the transition points.

◆ get_GJ()

const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > & Segment::get_GJ ( ) const

Implements a getter method for retrieving the torsional stiffness of the tubes in all of the tube segments in the CTR assembly.

Returns
A 3xN hybrid Blaze matrix containing the torsional stiffness [0, 0, k_z] for the tube assembly between the transition points.

◆ get_S()

const std::vector< double > & Segment::get_S ( ) const

Implements a getter method for retrieving all the transition points currently present in the CTR assembly.

Returns
A std::vector containing the arc-length values (in meters) at which there are tube transition points (where tube ends or where there's a step change in the tube's pre-curvatures).

◆ get_U_x()

const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > & Segment::get_U_x ( ) const

Implements a getter method for retrieving the pre-curvature of the tubes along the 'x' direction in all of the tube segments in the CTR assembly.

Returns
A 3xN hybrid Blaze matrix containing the pre-curvatures along the 'x' direction for the tubes in all segments. The 1st, 2nd, and 3rd row of the matrix correspond to the pre-curvatures of the 1st, 2nd, and 3rd tubes, where the 1st tube is the innermost one.

◆ get_U_y()

const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > & Segment::get_U_y ( ) const

Implements a getter method for retrieving the pre-curvature of the tubes along the 'y' direction in all of the tube segments in the CTR assembly.

Returns
A 3xN hybrid Blaze matrix containing the pre-curvatures along the 'y' direction for the tubes in all segments. The 1st, 2nd, and 3rd row of the matrix correspond to the pre-curvatures of the 1st, 2nd, and 3rd tubes, where the 1st tube is the innermost one.

◆ getDistalEnds()

const blaze::StaticVector< double, 3UL > & Segment::getDistalEnds ( ) const

Implements a getter method for retrieving the distal ends of all tubes in the CTR assembly.

Returns
A blaze::StaticVector containing the arc-length values (in meters) at which each tube in the CTR assembly terminates.

◆ operator=() [1/2]

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

Implements the copy assignment operator for the Segment class.

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

◆ operator=() [2/2]

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

Implements the move assignment operator for the Segment class.

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

◆ recalculateSegments()

void Segment::recalculateSegments ( const std::array< std::shared_ptr< Tube >, 3UL > & Tb,
const blaze::StaticVector< double, 3UL > & beta )

Computes the tube transition points and the corresponding parameters at each segment.

Parameters
TbA 3-dimensional std::array containing smart pointers to the three tube objects comprising the CTR assembly.
betaA 3-dimensional static Blaze vector containing the actuation input values for the linear joints of the CTR.

◆ returnParameters()

std::tuple< const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > &, const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > &, const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > &, const blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > &, const std::vector< double > & > Segment::returnParameters ( ) const

Implements a getter method for retrieving all parameters along all segments in the CTR assembly.

Returns
A Tuple containing: a 3xN Blaze matrix of the bending stiffness (EI), a 3xN Blaze matrix of the torsional stiffness (GJ), a 3xN Blaze matrix of the pre-curvature along the 'x' direction (U_x), a 3xN Blaze matrix of the pre-curvature along the 'y' direction (U_y), and a std::vector with the arc-length (in meters) at which a tube transition occurs (S).

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