Public Member Functions | Public Attributes
labust::allocation::EThruster Class Reference

#include <ethruster.h>

List of all members.

Public Member Functions

 EThruster ()
 Main constructor.
 EThruster (double Kp, double Kn, int pwm_id, double pwm_max, double pwm_min, double pwm_dir)
 Init constructor.
double F (double p=1, double Us=1)
double pwm (double F, double Us=1)

Public Attributes

double Kn
 The Kn- gain for negative voltages.
double Kp
 The Kn+ gain for positive voltages.
int pwm_dir
 The pwm corrected direction.
int pwm_id
 The connected PWM id.
double pwm_max
 The maximum pwm.
double pwm_min
 The minimum pwm.

Detailed Description

The class implements a object representation of a single electrical thruster with the standard quadratic characteristics.

F = K*Ua*|Ua| = Kn*Us^2*p|p| where: Ua - general Ua voltage Us - current supply voltage (Us>0) K - the thruster gain (Kp for positive, Kn for negative); K,Kp,Kn>0 p - PWM width [-1,1] F - the supplied thruster force

Definition at line 55 of file ethruster.h.


Constructor & Destructor Documentation

Main constructor.

Definition at line 59 of file ethruster.h.

labust::allocation::EThruster::EThruster ( double  Kp,
double  Kn,
int  pwm_id,
double  pwm_max,
double  pwm_min,
double  pwm_dir 
) [inline]

Init constructor.

Definition at line 68 of file ethruster.h.


Member Function Documentation

double labust::allocation::EThruster::F ( double  p = 1,
double  Us = 1 
) [inline]

Calculate the force given a supply voltage and PWM value.

Parameters:
Us- the supply voltage (default: 1)
p- the PWM values (default: 1)

Definition at line 82 of file ethruster.h.

double labust::allocation::EThruster::pwm ( double  F,
double  Us = 1 
) [inline]

Calculate the required pwm value given a desired force.

Parameters:
Us- the supply voltage (default: 1)
p- the PWM values (default: 1)
Returns:

Definition at line 89 of file ethruster.h.


Member Data Documentation

The Kn- gain for negative voltages.

Definition at line 98 of file ethruster.h.

The Kn+ gain for positive voltages.

Definition at line 96 of file ethruster.h.

The pwm corrected direction.

Definition at line 106 of file ethruster.h.

The connected PWM id.

Definition at line 100 of file ethruster.h.

The maximum pwm.

Definition at line 102 of file ethruster.h.

The minimum pwm.

Definition at line 104 of file ethruster.h.


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


labust_allocation
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:23:28