Barebones Static CTR Library 2.1.4
All Classes Functions Variables Pages
ODESystem.hpp
1#pragma once
2
3#include <blaze/Math.h>
4#include "mathOperations.hpp"
5
6typedef blaze::StaticVector<double, 15UL> state_type;
7
12{
13private:
18 blaze::StaticVector<double, 3UL> m_u_ast_x;
19
24 blaze::StaticVector<double, 3UL> m_u_ast_y;
25
30 blaze::StaticVector<double, 3UL> m_EI;
31
36 blaze::StaticVector<double, 3UL> m_GJ;
37
41 blaze::StaticVector<double, 3UL> m_e3;
42
46 blaze::StaticVector<double, 3UL> m_f;
47
48public:
52 ODESystem();
53
62 ODESystem(const blaze::StaticVector<double, 3UL> &u_ast_x, const blaze::StaticVector<double, 3UL> &u_ast_y, const blaze::StaticVector<double, 3UL> &EI, const blaze::StaticVector<double, 3UL> &GJ);
63
69 ODESystem(const ODESystem &rhs);
70
76 ODESystem(ODESystem &&rhs) noexcept;
77
81 ~ODESystem() = default;
82
89 ODESystem &operator=(const ODESystem &rhs);
90
97 ODESystem &operator=(ODESystem &&rhs) noexcept;
98
106 void operator()(const state_type &y, state_type &dyds, const double s) noexcept;
107
117 void setEquationParameters(const blaze::StaticVector<double, 3UL> &u_ast_x,
118 const blaze::StaticVector<double, 3UL> &u_ast_y,
119 const blaze::StaticVector<double, 3UL> &EI,
120 const blaze::StaticVector<double, 3UL> &GJ,
121 const blaze::StaticVector<double, 3UL> &force);
122};
Implements system of Ordinary Differential equations (ODEs) that model the kinematics of a three-tube...
Definition ODESystem.hpp:12
blaze::StaticVector< double, 3UL > m_GJ
Torsional stiffness of each tube in the current segment. If a tube is not present in the current segm...
Definition ODESystem.hpp:36
blaze::StaticVector< double, 3UL > m_u_ast_y
Pre-curvature of the tubes along the 'y' direction in the current segment. The i-th entry of the vect...
Definition ODESystem.hpp:24
ODESystem()
Implements the default constructor for the ODESystem class.
Definition ODESystem.cpp:6
blaze::StaticVector< double, 3UL > m_EI
Bending stiffness of each of the tubes in the current segment. If a tube is not present in the curren...
Definition ODESystem.hpp:30
~ODESystem()=default
Destroys the ODESystem object.
blaze::StaticVector< double, 3UL > m_f
Point force acting at the distal end of the CTR.
Definition ODESystem.hpp:46
void operator()(const state_type &y, state_type &dyds, const double s) noexcept
Functor that overloads the constructor's signature and implements the system of ODEs governing a thre...
Definition ODESystem.cpp:69
void setEquationParameters(const blaze::StaticVector< double, 3UL > &u_ast_x, const blaze::StaticVector< double, 3UL > &u_ast_y, const blaze::StaticVector< double, 3UL > &EI, const blaze::StaticVector< double, 3UL > &GJ, const blaze::StaticVector< double, 3UL > &force)
Implements a setter method for updating the kinematic parameters before computation of the ODEs at ea...
Definition ODESystem.cpp:152
ODESystem & operator=(const ODESystem &rhs)
Implements the copy assignment operator for the ODESystem class.
Definition ODESystem.cpp:37
blaze::StaticVector< double, 3UL > m_e3
A unit vector in the z-direction.
Definition ODESystem.hpp:41
blaze::StaticVector< double, 3UL > m_u_ast_x
Pre-curvature of the tubes along the 'x' direction in the current segment. The i-th entry of the vect...
Definition ODESystem.hpp:18