Barebones Static CTR Library 2.1.4
Loading...
Searching...
No Matches
CTR.hpp
1// ***************************************************************************************** //
2// * This file is part of NIH_CSTAR, a CTR kinematics library for Concentric Tube Robots * //
3// * * //
4// * ----------- # Copyright (C) 2021 Filipe C. Pedrosa <fpedrosa@uwo.ca> # ----------- * //
5// * * //
6// * Project developed under the supervision of Prof Dr Rajni Patel <rvpatel@uwo.ca> * //
7// * CSTAR (Canadian Surgical Technologies & Advanced Robotics) * //
8// * Western University, London, ON, Canada * //
9// ***************************************************************************************** //
10
11#pragma once
12
13#include "Tube.hpp"
14#include "Segment.hpp"
15#include "ODESystem.hpp"
16#include "Observer.hpp"
17#include "mathOperations.hpp"
18#include <boost/numeric/odeint.hpp>
19#include <memory>
20#include <tuple>
21
25class CTR
26{
27public:
31 CTR() = delete;
32
41 CTR(const std::array<std::shared_ptr<Tube>, 3UL> &Tb, blaze::StaticVector<double, 6UL> &q, const double Tol, const mathOp::rootFindingMethod method);
42
48 CTR(const CTR &rhs);
49
55 CTR(CTR &&rhs) noexcept;
56
60 ~CTR() = default;
61
68 CTR &operator=(const CTR &rhs);
69
76 CTR &operator=(CTR &&rhs) noexcept;
77
83 void reset(const blaze::StaticVector<double, 5UL> &initGuess);
84
91 blaze::StaticVector<double, 5UL> ODESolver(const blaze::StaticVector<double, 5UL> &initGuess);
92
100 blaze::StaticMatrix<double, 5UL, 5UL> jac_BVP(const blaze::StaticVector<double, 5UL> &initGuess, const blaze::StaticVector<double, 5UL> &residue);
101
109 blaze::StaticMatrix<double, 3UL, 6UL> jacobian(const blaze::StaticVector<double, 5UL> &initGuess, const blaze::StaticVector<double, 3UL> &tipPos);
110
117 bool PowellDogLeg(blaze::StaticVector<double, 5UL> &initGuess);
118
125 bool Levenberg_Marquardt(blaze::StaticVector<double, 5UL> &initGuess);
126
133 bool Broyden(blaze::StaticVector<double, 5UL> &initGuess);
134
141 bool Broyden_II(blaze::StaticVector<double, 5UL> &initGuess);
142
149 bool Newton_Raphson(blaze::StaticVector<double, 5UL> &initGuess);
150
157 bool Modified_Newton_Raphson(blaze::StaticVector<double, 5UL> &initGuess);
158
166 bool actuate_CTR(blaze::StaticVector<double, 5UL> &initGuess, const blaze::StaticVector<double, 6UL> &q_input);
167
176 bool posCTRL(blaze::StaticVector<double, 5UL> &initGuess, const blaze::StaticVector<double, 3UL> &target, const double Tol);
177
183 std::array<std::shared_ptr<Tube>, 3UL> getTubes();
184
190 blaze::StaticVector<double, 3UL> getBeta();
191
197 blaze::StaticVector<double, 6UL> getConfiguration();
198
204 blaze::StaticVector<double, 3UL> getTipPos();
205
211 blaze::StaticVector<double, 3UL> getDistalEnds();
212
218 std::tuple<blaze::HybridMatrix<double, 3UL, 1000UL, blaze::columnMajor>, blaze::HybridMatrix<double, 3UL, 1000UL, blaze::columnMajor>, blaze::HybridMatrix<double, 3UL, 1000UL, blaze::columnMajor>> getTubeShapes();
219
225 std::tuple<std::vector<double>, std::vector<double>, std::vector<double>> getShape();
226
232 void setConfiguration(const blaze::StaticVector<double, 6UL> &q);
233
239 void setBVPMethod(mathOp::rootFindingMethod mthd);
240
246 void setDistalMoment(const blaze::StaticVector<double, 3UL> &moment);
247
253 void setDistalForce(const blaze::StaticVector<double, 3UL> &force);
254
255private:
260
264 mathOp::rootFindingMethod m_method;
265
269 std::array<std::shared_ptr<Tube>, 3UL> m_Tubes;
270
274 blaze::StaticVector<double, 3UL> m_beta;
275
279 blaze::StaticVector<double, 6UL> m_q;
280
284 blaze::StaticVector<double, 3UL> m_theta_0;
285
289 blaze::StaticVector<double, 4UL> m_h_0;
290
294 blaze::StaticVector<double, 3UL> m_wf;
295
299 blaze::StaticVector<double, 3UL> m_wm;
300
304 blaze::StaticVector<double, 3UL> m_e3;
305
309 std::unique_ptr<Segment> m_segment;
310
314 std::vector<state_type> m_y;
315
319 std::vector<double> m_s;
320
324 std::unique_ptr<ODESystem> m_stateEquations;
325
329 std::unique_ptr<Observer> m_stateObserver;
330};
Class implementing a three-tube Concentric Tube Robot (CTR).
Definition CTR.hpp:26
blaze::StaticVector< double, 3UL > m_wm
External point moment at the distal-end of the CTR (moment component of the external wrench).
Definition CTR.hpp:299
CTR & operator=(const CTR &rhs)
Implements the copy assignment operator for the CTR class.
Definition CTR.cpp:55
bool Broyden_II(blaze::StaticVector< double, 5UL > &initGuess)
Nonlinear root-finding algorithm for solving the shooting method. It implements the Broyden's Method ...
Definition CTR.cpp:567
blaze::StaticVector< double, 3UL > getDistalEnds()
Returns the arc-lenghts of each tube's distal end in meters.
Definition CTR.cpp:1101
std::vector< state_type > m_y
Stores the CTR state vector at each arc-length (spatial integration step).
Definition CTR.hpp:314
CTR()=delete
Removes the default CTR Class constructor.
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.
Definition CTR.cpp:1107
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)
Definition CTR.cpp:260
bool PowellDogLeg(blaze::StaticVector< double, 5UL > &initGuess)
Nonlinear root-finding algorithm for solving the shooting method. It implements the Powell's Dog Leg ...
Definition CTR.cpp:321
blaze::StaticVector< double, 3UL > m_e3
Third canonical basis of R^3.
Definition CTR.hpp:304
bool Levenberg_Marquardt(blaze::StaticVector< double, 5UL > &initGuess)
Nonlinear root-finding algorithm for solving the shooting method. It implements the Levenberg-Marquar...
Definition CTR.cpp:423
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.
Definition CTR.cpp:1184
blaze::StaticVector< double, 5UL > ODESolver(const blaze::StaticVector< double, 5UL > &initGuess)
Solves the CTR model equations (system of ODEs) by numerical integration.
Definition CTR.cpp:130
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.
Definition CTR.cpp:871
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.
Definition CTR.cpp:1179
std::array< std::shared_ptr< Tube >, 3UL > getTubes()
Returns an std container with smart pointers to the Tube objects comprising the CTR.
Definition CTR.cpp:1073
blaze::StaticVector< double, 3UL > m_beta
Linear actuation values [beta_1, beta_2, beta_3].
Definition CTR.hpp:274
bool Modified_Newton_Raphson(blaze::StaticVector< double, 5UL > &initGuess)
Nonlinear root-finding algorithm for solving the shooting method. It implements the modified Newton-R...
Definition CTR.cpp:706
void reset(const blaze::StaticVector< double, 5UL > &initGuess)
Resets the std::vector containing all state variables for the CTR at each arc-length.
Definition CTR.cpp:107
std::unique_ptr< Observer > m_stateObserver
Unique pointer to the state observer for Boost::odeInt.
Definition CTR.hpp:329
blaze::StaticVector< double, 4UL > m_h_0
Initial orientation of the local frame at s = 0, represented as a quaternion.
Definition CTR.hpp:289
bool Broyden(blaze::StaticVector< double, 5UL > &initGuess)
Nonlinear root-finding algorithm for solving the shooting method. It implements the Broyden's Method ...
Definition CTR.cpp:489
blaze::StaticVector< double, 6UL > m_q
Joint actuation values [alpha_1, alpha_2, alpha_3].
Definition CTR.hpp:279
blaze::StaticVector< double, 3UL > getBeta()
Returns the current actuation values of the linear joints of the CTR.
Definition CTR.cpp:1079
mathOp::rootFindingMethod m_method
Available root-finding methods: Newton-Raphson, Levenberg-Marquardt, Powell (dog-leg),...
Definition CTR.hpp:264
~CTR()=default
Destroys the CTR object.
void setBVPMethod(mathOp::rootFindingMethod mthd)
Implements a setter method for chosing wich nonlinear root finding algorithm to use when solving the ...
Definition CTR.cpp:1174
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...
Definition CTR.cpp:1146
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.
Definition CTR.cpp:286
std::vector< double > m_s
Stores the discrete arc-length points (in meters) along the backbone.
Definition CTR.hpp:319
bool Newton_Raphson(blaze::StaticVector< double, 5UL > &initGuess)
Nonlinear root-finding algorithm for solving the shooting method. It implements the Newton-Raphson's ...
Definition CTR.cpp:644
std::unique_ptr< Segment > m_segment
Unique pointer to the segments between transition points along the CTR backbone.
Definition CTR.hpp:309
blaze::StaticVector< double, 3UL > getTipPos()
Returns the current end-effector (distal-end) position of the CTR in meters.
Definition CTR.cpp:1091
std::unique_ptr< ODESystem > m_stateEquations
Unique pointer to the ODE system implementing the state differential equations for a three-tube CTR.
Definition CTR.hpp:324
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 ...
Definition CTR.cpp:1167
blaze::StaticVector< double, 3UL > m_wf
External point force at the distal-end of the CTR (force component of the external wrench).
Definition CTR.hpp:294
blaze::StaticVector< double, 3UL > m_theta_0
Initial twist angle for all tubes at s = 0.
Definition CTR.hpp:284
std::array< std::shared_ptr< Tube >, 3UL > m_Tubes
Array of smart pointers to the Tube objects comprising the CTR.
Definition CTR.hpp:269
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 bound...
Definition CTR.cpp:833
double m_accuracy
Defines the accuracy of the numerical solution for the CTR Boundary Value Problem (BVP).
Definition CTR.hpp:259
blaze::StaticVector< double, 6UL > getConfiguration()
Returns the current actuation values of all the linear and revolute joints of the CTR.
Definition CTR.cpp:1085