#include <ThrustAllocation.hpp>
| Public Member Functions | |
| void | configure (ros::NodeHandle &nh) | 
| Load and configure allocation parameters from the parameter server. | |
| ThrustAllocation () | |
| Main constructor initializes the values to a normalized differential surface robot configuration. | |
| Public Attributes | |
| Eigen::MatrixXd | B | 
| The allocation matrix. | |
| Eigen::MatrixXd | Binv | 
| Ideal inverse allocation matrix. | |
| Eigen::VectorXi | dofs | 
| Used Degrees of Freedom (surge = 0, sway, heave, roll, pitch, yaw). | |
| int | pwmscaler | 
| The pwm scaler. | |
| Eigen::VectorXd | tmax | 
| Maximum thrust available per thruster. | |
| Eigen::VectorXd | tmin | 
| Minimum thrust available per thruster. | |
| Eigen::MatrixXd | W | 
| Weight matrix. | |
Contains the variables and the basic scaling allocation which is needed.
Definition at line 52 of file ThrustAllocation.hpp.
Main constructor initializes the values to a normalized differential surface robot configuration.
Definition at line 45 of file ThrustAllocation.cpp.
| void ThrustAllocation::configure | ( | ros::NodeHandle & | nh | ) | 
Load and configure allocation parameters from the parameter server.
Definition at line 60 of file ThrustAllocation.cpp.
| Eigen::MatrixXd labust::allocation::ThrustAllocation::B | 
The allocation matrix.
Definition at line 62 of file ThrustAllocation.hpp.
| Eigen::MatrixXd labust::allocation::ThrustAllocation::Binv | 
Ideal inverse allocation matrix.
Definition at line 64 of file ThrustAllocation.hpp.
| Eigen::VectorXi labust::allocation::ThrustAllocation::dofs | 
Used Degrees of Freedom (surge = 0, sway, heave, roll, pitch, yaw).
Definition at line 68 of file ThrustAllocation.hpp.
The pwm scaler.
Definition at line 74 of file ThrustAllocation.hpp.
| Eigen::VectorXd labust::allocation::ThrustAllocation::tmax | 
Maximum thrust available per thruster.
Definition at line 70 of file ThrustAllocation.hpp.
| Eigen::VectorXd labust::allocation::ThrustAllocation::tmin | 
Minimum thrust available per thruster.
Definition at line 72 of file ThrustAllocation.hpp.
| Eigen::MatrixXd labust::allocation::ThrustAllocation::W | 
Weight matrix.
Definition at line 66 of file ThrustAllocation.hpp.