Barebones Static CTR Library 2.1.4
All Classes Functions Variables Pages
Segment.hpp
1#pragma once
2
3#include <vector>
4#include <array>
5#include <algorithm>
6#include "Tube.hpp"
7
12{
13private:
17 std::vector<double> m_S;
18
22 blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> m_EI;
23
27 blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> m_GJ;
28
32 blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> m_U_x;
33
37 blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> m_U_y;
38
42 blaze::StaticVector<double, 3UL> m_len_curv;
43
47 blaze::StaticVector<double, 3UL> m_dist_end;
48
49public:
54
61 Segment(const std::array<std::shared_ptr<Tube>, 3UL> &Tb, const blaze::StaticVector<double, 3UL> &beta);
62
68 Segment(const Segment &rhs);
69
75 Segment(Segment &&rhs) noexcept;
76
80 ~Segment() = default;
81
88 Segment &operator=(const Segment &rhs);
89
96 Segment &operator=(Segment &&rhs) noexcept;
97
104 void recalculateSegments(const std::array<std::shared_ptr<Tube>, 3UL> &Tb, const blaze::StaticVector<double, 3UL> &beta);
105
111 const std::vector<double>& get_S() const;
112
118 const blaze::StaticVector<double, 3UL> &getDistalEnds() const;
119
125 const blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> &get_EI() const;
126
132 const blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> &get_GJ() const;
133
139 const blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> &get_U_x() const;
140
146 const blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> &get_U_y() const;
147
153 std::tuple<const blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> &,
154 const blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> &,
155 const blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> &,
156 const blaze::HybridMatrix<double, 3UL, 18UL, blaze::columnMajor> &,
157 const std::vector<double> &>
158 returnParameters() const;
159};
Class representing Segments between transition points in a Concentric Tube Robot (CTR).
Definition Segment.hpp:12
std::vector< double > m_S
Arc-length of each tube transition point.
Definition Segment.hpp:17
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 a...
Definition Segment.cpp:178
blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > m_EI
Tubes' bending stiffness – x, y directions.
Definition Segment.hpp:22
const blaze::StaticVector< double, 3UL > & getDistalEnds() const
Implements a getter method for retrieving the distal ends of all tubes in the CTR assembly.
Definition Segment.cpp:160
const std::vector< double > & get_S() const
Implements a getter method for retrieving all the transition points currently present in the CTR asse...
Definition Segment.cpp:154
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.
Definition Segment.cpp:195
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 seg...
Definition Segment.cpp:172
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.
Definition Segment.cpp:67
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 a...
Definition Segment.cpp:184
blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > m_U_y
Tubes' precurvature in the y direction.
Definition Segment.hpp:37
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 segme...
Definition Segment.cpp:166
Segment & operator=(const Segment &rhs)
Implements the copy assignment operator for the Segment class.
Definition Segment.cpp:33
blaze::StaticVector< double, 3UL > m_len_curv
Arc-length at which precurvature starts in the tubes.
Definition Segment.hpp:42
blaze::StaticVector< double, 3UL > m_dist_end
Arc-length at which the tubes terminate (distal-ends).
Definition Segment.hpp:47
blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > m_GJ
Tubes' torsional stiffness – z direction.
Definition Segment.hpp:27
~Segment()=default
Destroys the Segment object.
Segment()
Implements the default constructor for the Segment class.
blaze::HybridMatrix< double, 3UL, 18UL, blaze::columnMajor > m_U_x
Tubes' precurvature in the x direction.
Definition Segment.hpp:32