Implements system of Ordinary Differential equations (ODEs) that model the kinematics of a three-tube CTR.
More...
#include <ODESystem.hpp>
|
| ODESystem () |
| Implements the default constructor for the ODESystem class.
|
|
| 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) |
| Implements the overloaded constructor for the ODESystem class.
|
|
| ODESystem (const ODESystem &rhs) |
| Implements the copy constructor for the ODESystem class.
|
|
| ODESystem (ODESystem &&rhs) noexcept |
| Implements the move constructor for the ODESystem class.
|
|
| ~ODESystem ()=default |
| Destroys the ODESystem object.
|
|
ODESystem & | operator= (const ODESystem &rhs) |
| Implements the copy assignment operator for the ODESystem class.
|
|
ODESystem & | operator= (ODESystem &&rhs) noexcept |
| Implements the move assignment operator for the ODESystem class.
|
|
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 three-tube CTR.
|
|
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 each arc-length 's'.
|
|
|
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 vector corresponds to the pre-curvature in the x-direction for the i-th tube in the concentric arrangement.
|
|
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 vector corresponds to the pre-curvature in the y-direction for the i-th tube in the concentric arrangement.
|
|
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 current segment, the corresponding entry will be zero.
|
|
blaze::StaticVector< double, 3UL > | m_GJ |
| Torsional stiffness of each tube in the current segment. If a tube is not present in the current segment, the corresponding entry will be zero.
|
|
blaze::StaticVector< double, 3UL > | m_e3 |
| A unit vector in the z-direction.
|
|
blaze::StaticVector< double, 3UL > | m_f |
| Point force acting at the distal end of the CTR.
|
|
Implements system of Ordinary Differential equations (ODEs) that model the kinematics of a three-tube CTR.
◆ ODESystem() [1/3]
ODESystem::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 ) |
Implements the overloaded constructor for the ODESystem class.
- Parameters
-
u_ast_x | A 3-dimensional static Blaze vector of the pre-curvature of the tubes along the 'x' direction in the present segment. |
u_ast_y | A 3-dimensional static Blaze vector of the pre-curvature of the tubes along the 'x' direction in the present segment. |
EI | A 3-dimensional static Blaze vector of bending stiffness of each one of the tubes in the present segment. If the i-th tube isn't present in the current segment, the i-th entry of EI_i will be zero. |
GJ | A 3-dimensional static Blaze vector of torsional stiffness of each one of the tubes in the present segment. If the i-th tube isn't present in the current segment, the i-th entry of GJ_i will be zero. |
◆ ODESystem() [2/3]
ODESystem::ODESystem |
( |
const ODESystem & | rhs | ) |
|
Implements the copy constructor for the ODESystem class.
- Parameters
-
◆ ODESystem() [3/3]
Implements the move constructor for the ODESystem class.
- Parameters
-
◆ operator()()
void ODESystem::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 three-tube CTR.
- Parameters
-
y | A 15-dimensional static Blaze vector containing the current values of the state vector at the arc-length 's' within the current segment. |
dyds | A 15-dimensional static Blaze vector to be computed by the functor. Once the functor is executed, 'dyds' corresponds to the spatial derivative of the state vector at the arc-length 's'. |
s | The nonnegative scalar corresponding to the arc-length along the CTR backbone at which the computations are taking place |
◆ operator=() [1/2]
Implements the copy assignment operator for the ODESystem class.
- Parameters
-
- Returns
- A reference to the assigned ODESystem object.
◆ operator=() [2/2]
Implements the move assignment operator for the ODESystem class.
- Parameters
-
- Returns
- A reference to the assigned ODESystem object.
◆ setEquationParameters()
void ODESystem::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 each arc-length 's'.
- Parameters
-
u_ast_x | A 3-dimensional static Blaze vector of the pre-curvature of the tubes along the 'x' direction in the present segment. |
u_ast_y | A 3-dimensional static Blaze vector of the pre-curvature of the tubes along the 'x' direction in the present segment. |
EI | A 3-dimensional static Blaze vector of bending stiffness of each one of the tubes in the present segment. If the i-th tube isn't present in the current segment, the i-th entry of EI_i will be zero. |
GJ | A 3-dimensional static Blaze vector of torsional stiffness of each one of the tubes in the present segment. If the i-th tube isn't present in the current segment, the i-th entry of GJ_i will be zero. |
force | A 3-dimensional static Blaze vector containing the point force acting at the distal-end of the CTR. |
The documentation for this class was generated from the following files: