#include <thruster_configuration.h>
Public Member Functions | |
| const Eigen::MatrixXd & | B () const |
| The ideal allocation matrix. | |
| const Eigen::MatrixXd & | Binv () const |
| The ideal inverse allocation matrix. | |
| bool | configure (ros::NodeHandle &nh, ros::NodeHandle &ph) |
| Configure the thruster collection from a private handle. | |
| const Eigen::VectorXd & | Fa () const |
| The achieved thruster forces with the current pwm output. | |
| const Eigen::VectorXd & | maxF () |
| The maximum allowable thruster forces. | |
| const Eigen::VectorXd & | minF () |
| The minimum allowable thruster forces. | |
| const std::vector< double > & | pwm (const Eigen::VectorXd &F) |
| The pwm output calculation based on the supplied thruster forces. | |
| const std::vector< double > & | pwmFromTau (const Eigen::VectorXd &tau) |
| The pwm output calculation based on the supplied tau vector forces. | |
| const Eigen::VectorXd & | tauA () const |
| The achieved tau with the current pwm output. | |
| ThrusterConfiguration () | |
| Main constructor. | |
Private Member Functions | |
| void | onSupplyVoltage (const std_msgs::Float32::ConstPtr &voltage) |
| Handle supply voltage. | |
| void | updateMinMax () |
| Helper method for initialization of maximum and minimum thruster forces. | |
Private Attributes | |
| Eigen::MatrixXd | _B |
| Allocation matrix. | |
| Eigen::MatrixXd | _Binv |
| The inverse allocation matrix. | |
| bool | adapt |
| The pwm adaptation flag. | |
| Eigen::VectorXd | F_a |
| The achieved thrust forces after all coercions. | |
| Eigen::VectorXd | F_max |
| The maximum forces. | |
| Eigen::VectorXd | F_min |
| The minimum forces. | |
| std::vector< double > | pwm_out |
| The pwm output. | |
| Eigen::VectorXd | T_a |
| The achieved thrust forces after all coercions. | |
| std::vector< EThruster > | thrusters |
| Thruster collection. | |
| double | Un |
| The nominal motor voltage. | |
| double | Us |
| The current supply voltage. | |
| ros::Subscriber | voltage_sub |
| Supply voltage subscriber. | |
The class implements a object representation of a thruster configuration.
Definition at line 55 of file thruster_configuration.h.
Main constructor.
Definition at line 43 of file thruster_configuration.cpp.
| const Eigen::MatrixXd& labust::allocation::ThrusterConfiguration::B | ( | ) | const [inline] |
The ideal allocation matrix.
Definition at line 65 of file thruster_configuration.h.
| const Eigen::MatrixXd& labust::allocation::ThrusterConfiguration::Binv | ( | ) | const [inline] |
The ideal inverse allocation matrix.
Definition at line 67 of file thruster_configuration.h.
| bool ThrusterConfiguration::configure | ( | ros::NodeHandle & | nh, |
| ros::NodeHandle & | ph | ||
| ) |
Configure the thruster collection from a private handle.
Definition at line 48 of file thruster_configuration.cpp.
| const Eigen::VectorXd& labust::allocation::ThrusterConfiguration::Fa | ( | ) | const [inline] |
The achieved thruster forces with the current pwm output.
Definition at line 75 of file thruster_configuration.h.
| const Eigen::VectorXd& labust::allocation::ThrusterConfiguration::maxF | ( | ) | [inline] |
The maximum allowable thruster forces.
Definition at line 80 of file thruster_configuration.h.
| const Eigen::VectorXd& labust::allocation::ThrusterConfiguration::minF | ( | ) | [inline] |
The minimum allowable thruster forces.
Definition at line 82 of file thruster_configuration.h.
| void labust::allocation::ThrusterConfiguration::onSupplyVoltage | ( | const std_msgs::Float32::ConstPtr & | voltage | ) | [inline, private] |
Handle supply voltage.
Definition at line 86 of file thruster_configuration.h.
| const std::vector< double > & ThrusterConfiguration::pwm | ( | const Eigen::VectorXd & | F | ) |
The pwm output calculation based on the supplied thruster forces.
Definition at line 135 of file thruster_configuration.cpp.
| const std::vector<double>& labust::allocation::ThrusterConfiguration::pwmFromTau | ( | const Eigen::VectorXd & | tau | ) | [inline] |
The pwm output calculation based on the supplied tau vector forces.
Definition at line 72 of file thruster_configuration.h.
| const Eigen::VectorXd& labust::allocation::ThrusterConfiguration::tauA | ( | ) | const [inline] |
The achieved tau with the current pwm output.
Definition at line 70 of file thruster_configuration.h.
| void ThrusterConfiguration::updateMinMax | ( | ) | [private] |
Helper method for initialization of maximum and minimum thruster forces.
Definition at line 176 of file thruster_configuration.cpp.
Eigen::MatrixXd labust::allocation::ThrusterConfiguration::_B [private] |
Allocation matrix.
Definition at line 100 of file thruster_configuration.h.
Eigen::MatrixXd labust::allocation::ThrusterConfiguration::_Binv [private] |
The inverse allocation matrix.
Definition at line 102 of file thruster_configuration.h.
bool labust::allocation::ThrusterConfiguration::adapt [private] |
The pwm adaptation flag.
Definition at line 111 of file thruster_configuration.h.
Eigen::VectorXd labust::allocation::ThrusterConfiguration::F_a [private] |
The achieved thrust forces after all coercions.
Definition at line 117 of file thruster_configuration.h.
Eigen::VectorXd labust::allocation::ThrusterConfiguration::F_max [private] |
The maximum forces.
Definition at line 119 of file thruster_configuration.h.
Eigen::VectorXd labust::allocation::ThrusterConfiguration::F_min [private] |
The minimum forces.
Definition at line 121 of file thruster_configuration.h.
std::vector<double> labust::allocation::ThrusterConfiguration::pwm_out [private] |
The pwm output.
Definition at line 113 of file thruster_configuration.h.
Eigen::VectorXd labust::allocation::ThrusterConfiguration::T_a [private] |
The achieved thrust forces after all coercions.
Definition at line 115 of file thruster_configuration.h.
Thruster collection.
Definition at line 104 of file thruster_configuration.h.
double labust::allocation::ThrusterConfiguration::Un [private] |
The nominal motor voltage.
Definition at line 109 of file thruster_configuration.h.
double labust::allocation::ThrusterConfiguration::Us [private] |
The current supply voltage.
Definition at line 107 of file thruster_configuration.h.
Supply voltage subscriber.
Definition at line 97 of file thruster_configuration.h.