Classes | Public Member Functions | Private Attributes | List of all members
rosflight_sim::Fixedwing Class Reference

#include <fixedwing_forces_and_moments.h>

Inheritance diagram for rosflight_sim::Fixedwing:
Inheritance graph
[legend]

Classes

struct  Actuators
 
struct  LiftCoeff
 
struct  PropCoeff
 
struct  WingCoeff
 

Public Member Functions

 Fixedwing (ros::NodeHandle *nh)
 
void set_wind (Eigen::Vector3d wind)
 
Eigen::Matrix< double, 6, 1 > updateForcesAndTorques (Current_State x, const int act_cmds[])
 
 ~Fixedwing ()
 

Private Attributes

LiftCoeff CD_
 
LiftCoeff Cell_
 
LiftCoeff CL_
 
LiftCoeff Cm_
 
LiftCoeff Cn_
 
LiftCoeff CY_
 
struct rosflight_sim::Fixedwing::Actuators delta_
 
double Jx_
 
double Jxz_
 
double Jy_
 
double Jz_
 
double mass_
 
ros::NodeHandlenh_
 
struct rosflight_sim::Fixedwing::PropCoeff prop_
 
double rho_
 
Eigen::Vector3d wind_
 
struct rosflight_sim::Fixedwing::WingCoeff wing_
 

Additional Inherited Members

- Protected Member Functions inherited from rosflight_sim::MAVForcesAndMoments
double max (double x, double y)
 
double sat (double x, double max, double min)
 

Detailed Description

Definition at line 43 of file fixedwing_forces_and_moments.h.

Constructor & Destructor Documentation

rosflight_sim::Fixedwing::Fixedwing ( ros::NodeHandle nh)

Definition at line 37 of file fixedwing_forces_and_moments.cpp.

rosflight_sim::Fixedwing::~Fixedwing ( )

Member Function Documentation

void rosflight_sim::Fixedwing::set_wind ( Eigen::Vector3d  wind)
virtual
Eigen::Matrix< double, 6, 1 > rosflight_sim::Fixedwing::updateForcesAndTorques ( Current_State  x,
const int  act_cmds[] 
)
virtual

Member Data Documentation

LiftCoeff rosflight_sim::Fixedwing::CD_
private

Definition at line 90 of file fixedwing_forces_and_moments.h.

LiftCoeff rosflight_sim::Fixedwing::Cell_
private

Definition at line 93 of file fixedwing_forces_and_moments.h.

LiftCoeff rosflight_sim::Fixedwing::CL_
private

Definition at line 89 of file fixedwing_forces_and_moments.h.

LiftCoeff rosflight_sim::Fixedwing::Cm_
private

Definition at line 91 of file fixedwing_forces_and_moments.h.

LiftCoeff rosflight_sim::Fixedwing::Cn_
private

Definition at line 94 of file fixedwing_forces_and_moments.h.

LiftCoeff rosflight_sim::Fixedwing::CY_
private

Definition at line 92 of file fixedwing_forces_and_moments.h.

struct rosflight_sim::Fixedwing::Actuators rosflight_sim::Fixedwing::delta_
private
double rosflight_sim::Fixedwing::Jx_
private

Definition at line 50 of file fixedwing_forces_and_moments.h.

double rosflight_sim::Fixedwing::Jxz_
private

Definition at line 53 of file fixedwing_forces_and_moments.h.

double rosflight_sim::Fixedwing::Jy_
private

Definition at line 51 of file fixedwing_forces_and_moments.h.

double rosflight_sim::Fixedwing::Jz_
private

Definition at line 52 of file fixedwing_forces_and_moments.h.

double rosflight_sim::Fixedwing::mass_
private

Definition at line 49 of file fixedwing_forces_and_moments.h.

ros::NodeHandle* rosflight_sim::Fixedwing::nh_
private

Definition at line 46 of file fixedwing_forces_and_moments.h.

struct rosflight_sim::Fixedwing::PropCoeff rosflight_sim::Fixedwing::prop_
private
double rosflight_sim::Fixedwing::rho_
private

Definition at line 54 of file fixedwing_forces_and_moments.h.

Eigen::Vector3d rosflight_sim::Fixedwing::wind_
private

Definition at line 106 of file fixedwing_forces_and_moments.h.

struct rosflight_sim::Fixedwing::WingCoeff rosflight_sim::Fixedwing::wing_
private

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


rosflight_sim
Author(s): James Jackson, Gary Ellingson, Daniel Koch
autogenerated on Wed Jul 3 2019 20:00:29