|
MFCPP
1.0
|
Corentin Chauvin-Hameau – 2019-2020
|
|
Coverage Path Planning for an underwater robot surveying a marine farm
|
|
Class defining the robot model. More...
#include <robot_model.hpp>
Public Types | |
| typedef std::vector< double > | state_type |
| Data type of the state. More... | |
| typedef std::vector< double > | input_type |
| Data type of the input. More... | |
Public Member Functions | |
| RobotModel () | |
| RobotModel (const std::vector< double > &c) | |
| ~RobotModel () | |
| void | eval_ode (const state_type &x, const input_type &u, state_type &dxdt, const double t) |
| Evaluate the ODE. More... | |
| void | integrate (state_type &state, const input_type &input, double t1, double t2, double init_step) |
| Integrates the model over a period of time. More... | |
| template<class MatrixT > | |
| void | get_lin_matrices (const state_type &x_0, const input_type &u_0, MatrixT &A, MatrixT &B) const |
| Gets the matrices of the linearised system. More... | |
| template<class MatrixT > | |
| void | get_lin_discr_matrices (const state_type &x_0, const input_type &u_0, MatrixT &Ad, MatrixT &Bd, float dt) const |
| Gets the matrices of the discretised linearised system. More... | |
| template<class VectorT , class MatrixT > | |
| void | get_lin_discr_matrices (const VectorT &x_0, const VectorT &u_0, MatrixT &Ad, MatrixT &Bd, float dt) const |
| Overloads get_lin_discr_matrices for Eigen vectors. More... | |
| double | steady_propeller_speed (double speed) const |
| Computes the propeller speed in steady state. More... | |
| double | steady_speed (double n) const |
| Computes the horizontal speed in steady state. More... | |
| double | lat_turn_radius (double u, double delta_r) const |
| Computes the lateral turning radius. More... | |
| double | elev_turn_radius (double u, double delta_e) const |
| Computes the elevation turning radius. More... | |
Private Member Functions | |
| void | ode (const state_type &x, state_type &dxdt, const double t) |
| ODE used to integrate the model. More... | |
| Eigen::Matrix3d | jac_pos (double phi, double theta, double psi) |
| Computes the Jacobian of the position. More... | |
| Eigen::Matrix3d | jac_orient (double phi, double theta, double psi) |
| Computes the Jacobian of the orientation. More... | |
| double | sign (double x) const |
| Returns the sign of a real number. More... | |
Private Attributes | |
| std::vector< double > | c_ |
| Model constants. More... | |
| double | g_ |
| Gravity acceleration. More... | |
| input_type | u_ |
| Model inputs. More... | |
Class defining the robot model.
The state is as follow:













The inputs are as follow:



Definition at line 47 of file robot_model.hpp.
| typedef std::vector<double> mfcpp::RobotModel::input_type |
Data type of the input.
Definition at line 54 of file robot_model.hpp.
| typedef std::vector<double> mfcpp::RobotModel::state_type |
Data type of the state.
Definition at line 51 of file robot_model.hpp.
| mfcpp::RobotModel::RobotModel | ( | ) |
Definition at line 32 of file robot_model.cpp.
| mfcpp::RobotModel::RobotModel | ( | const std::vector< double > & | c | ) |
| mfcpp::RobotModel::~RobotModel | ( | ) |
Definition at line 45 of file robot_model.cpp.
|
inline |
Computes the elevation turning radius.
| u | Speed of the robot |
| delta_e | Angle of the elevation rudder |
Definition at line 251 of file robot_model.hpp.
| void mfcpp::RobotModel::eval_ode | ( | const state_type & | x, |
| const input_type & | u, | ||
| state_type & | dxdt, | ||
| const double | t | ||
| ) |
Evaluate the ODE.
Public version of the ODE
| x | Current state |
| u | Current input |
| dxdt | Current time derivative of the state |
| t | Current time |
Definition at line 204 of file robot_model.cpp.
| void mfcpp::RobotModel::get_lin_discr_matrices | ( | const state_type & | x_0, |
| const input_type & | u_0, | ||
| MatrixT & | Ad, | ||
| MatrixT & | Bd, | ||
| float | dt | ||
| ) | const |
Gets the matrices of the discretised linearised system.
The system
is discretised by
and
.
MatrixT can either be Eigen::MatrixXd or Eigen::MatrixXf
| [in] | x_0 | Nominal state |
| [in] | u_0 | Nominal input |
| [out] | Ad | Discretised A matrix |
| [out] | Bd | Discretised B matrix |
| [in] | dt | Discretisation interval |
Definition at line 148 of file robot_model.cpp.
| void mfcpp::RobotModel::get_lin_discr_matrices | ( | const VectorT & | x_0, |
| const VectorT & | u_0, | ||
| MatrixT & | Ad, | ||
| MatrixT & | Bd, | ||
| float | dt | ||
| ) | const |
Overloads get_lin_discr_matrices for Eigen vectors.
VectorT can either be Eigen::VectorXd or Eigen::VectorXf MatrixT can either be Eigen::MatrixXd or Eigen::MatrixXf
Definition at line 166 of file robot_model.cpp.
| template void mfcpp::RobotModel::get_lin_matrices | ( | const state_type & | x_0, |
| const input_type & | u_0, | ||
| MatrixT & | A, | ||
| MatrixT & | B | ||
| ) | const |
Gets the matrices of the linearised system.
If the system is linearised around
, the system can be expressed for new variables
. The ODE then becomes:
.
MatrixT can either be Eigen::MatrixXd or Eigen::MatrixXf
| [in] | x_0 | Nominal state |
| [in] | u_0 | Nominal input |
| [out] | A | A matrix |
| [out] | B | B matrix |
Definition at line 64 of file robot_model.cpp.
| void mfcpp::RobotModel::integrate | ( | state_type & | state, |
| const input_type & | input, | ||
| double | t1, | ||
| double | t2, | ||
| double | init_step | ||
| ) |
Integrates the model over a period of time.
It will update the state by integrating the dynamic model of the robot. It assumes that the inputs are constant during the integration.
It is based on the error-controlled runge_kutta54_cash_karp stepper (5th order) and uses adaptive step-size.
| [in,out] | state | Initial state to update |
| [in] | input | Input to the actuators |
| [in] | t1 | Starting time of the integration |
| [in] | t2 | Ending time of the integration |
| [in] | init_step | Initial step size for the integration |
Definition at line 51 of file robot_model.cpp.
|
private |
Computes the Jacobian of the orientation.
Transforms angular velocities in the global frame to the inertial frame.
| phi | First angle of the robot's orientation |
| theta | Second angle of the robot's orientation |
| psi | Third angle of the robot's orientation |
Definition at line 248 of file robot_model.cpp.
|
private |
Computes the Jacobian of the position.
Transforms linear velocities in the global frame to the intertial frame.
| phi | First angle of the robot's orientation |
| theta | Second angle of the robot's orientation |
| psi | Third angle of the robot's orientation |
Definition at line 229 of file robot_model.cpp.
|
inline |
Computes the lateral turning radius.
| u | Speed of the robot |
| delta_r | Angle of the lateral rudder |
Definition at line 241 of file robot_model.hpp.
|
private |
ODE used to integrate the model.
| x | Current state |
| dxdt | Current time derivative of the state |
| t | Current time |
Definition at line 179 of file robot_model.cpp.
|
inlineprivate |
Returns the sign of a real number.
Definition at line 261 of file robot_model.hpp.
|
inline |
Computes the propeller speed in steady state.
| speed | Desired steady state speed |
Definition at line 227 of file robot_model.hpp.
|
inline |
Computes the horizontal speed in steady state.
| n | Rotational speed of the propeller |
Definition at line 234 of file robot_model.hpp.
|
private |
Model constants.
Definition at line 175 of file robot_model.hpp.
|
private |
Gravity acceleration.
Definition at line 178 of file robot_model.hpp.
|
private |
Model inputs.
Definition at line 181 of file robot_model.hpp.
1.8.11