Corentin Chauvin-Hameau – 2019-2020
Coverage Path Planning for an underwater robot surveying a marine farm
Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
mfcpp::RobotModel Class Reference

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...
 

Detailed Description

Class defining the robot model.

The state is as follow:

The inputs are as follow:

Definition at line 47 of file robot_model.hpp.

Member Typedef Documentation

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.

Constructor & Destructor Documentation

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.

Member Function Documentation

double mfcpp::RobotModel::elev_turn_radius ( double  u,
double  delta_e 
) const
inline

Computes the elevation turning radius.

Parameters
uSpeed of the robot
delta_eAngle 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

Parameters
xCurrent state
uCurrent input
dxdtCurrent time derivative of the state
tCurrent time

Definition at line 204 of file robot_model.cpp.

template<class MatrixT >
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 $ \dot{\Delta x} = A \Delta x + B \Delta u $ is discretised by $ A_d = e^{dt.A} $ and $ B_d = (\int_{0}^{dt} e^{s.A} ds) B $.

Todo:
Update how to get B_d

MatrixT can either be Eigen::MatrixXd or Eigen::MatrixXf

Parameters
[in]x_0Nominal state
[in]u_0Nominal input
[out]AdDiscretised A matrix
[out]BdDiscretised B matrix
[in]dtDiscretisation interval

Definition at line 148 of file robot_model.cpp.

template<class VectorT , class MatrixT >
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<class MatrixT >
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 $ (x_0, u_0) $, the system can be expressed for new variables $ (\Delta x, \Delta u) = (x-x_0, u-u_0) $. The ODE then becomes: $ \dot{\Delta x} = A \Delta x + B \Delta u $.

MatrixT can either be Eigen::MatrixXd or Eigen::MatrixXf

Parameters
[in]x_0Nominal state
[in]u_0Nominal input
[out]AA matrix
[out]BB 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.

Parameters
[in,out]stateInitial state to update
[in]inputInput to the actuators
[in]t1Starting time of the integration
[in]t2Ending time of the integration
[in]init_stepInitial step size for the integration

Definition at line 51 of file robot_model.cpp.

Matrix3d mfcpp::RobotModel::jac_orient ( double  phi,
double  theta,
double  psi 
)
private

Computes the Jacobian of the orientation.

Transforms angular velocities in the global frame to the inertial frame.

Parameters
phiFirst angle of the robot's orientation
thetaSecond angle of the robot's orientation
psiThird angle of the robot's orientation
Returns
Jacobian of the orientation

Definition at line 248 of file robot_model.cpp.

Matrix3d mfcpp::RobotModel::jac_pos ( double  phi,
double  theta,
double  psi 
)
private

Computes the Jacobian of the position.

Transforms linear velocities in the global frame to the intertial frame.

Parameters
phiFirst angle of the robot's orientation
thetaSecond angle of the robot's orientation
psiThird angle of the robot's orientation
Returns
Jacobian of the position

Definition at line 229 of file robot_model.cpp.

double mfcpp::RobotModel::lat_turn_radius ( double  u,
double  delta_r 
) const
inline

Computes the lateral turning radius.

Parameters
uSpeed of the robot
delta_rAngle of the lateral rudder

Definition at line 241 of file robot_model.hpp.

void mfcpp::RobotModel::ode ( const state_type x,
state_type dxdt,
const double  t 
)
private

ODE used to integrate the model.

Parameters
xCurrent state
dxdtCurrent time derivative of the state
tCurrent time

Definition at line 179 of file robot_model.cpp.

double mfcpp::RobotModel::sign ( double  x) const
inlineprivate

Returns the sign of a real number.

Returns
1 if x>=0, -1 otherwise

Definition at line 261 of file robot_model.hpp.

double mfcpp::RobotModel::steady_propeller_speed ( double  speed) const
inline

Computes the propeller speed in steady state.

Note
This assumes that delta_m = 0
Parameters
speedDesired steady state speed

Definition at line 227 of file robot_model.hpp.

double mfcpp::RobotModel::steady_speed ( double  n) const
inline

Computes the horizontal speed in steady state.

Note
This assumes that the propeller speed is constant and the robot is horizontal
Parameters
nRotational speed of the propeller

Definition at line 234 of file robot_model.hpp.

Member Data Documentation

std::vector<double> mfcpp::RobotModel::c_
private

Model constants.

Warning
c[0] is not used to respect notation

Definition at line 175 of file robot_model.hpp.

double mfcpp::RobotModel::g_
private

Gravity acceleration.

Definition at line 178 of file robot_model.hpp.

input_type mfcpp::RobotModel::u_
private

Model inputs.

Definition at line 181 of file robot_model.hpp.


The documentation for this class was generated from the following files: