#include <quadrotor_aerodynamics.h>
Definition at line 44 of file quadrotor_aerodynamics.h.
hector_quadrotor_model::QuadrotorAerodynamics::QuadrotorAerodynamics |
( |
| ) |
|
hector_quadrotor_model::QuadrotorAerodynamics::~QuadrotorAerodynamics |
( |
| ) |
|
void hector_quadrotor_model::QuadrotorAerodynamics::f |
( |
const double |
uin[6], |
|
|
double |
dt, |
|
|
double |
y[6] |
|
) |
| const |
|
inline |
const geometry_msgs::Wrench& hector_quadrotor_model::QuadrotorAerodynamics::getWrench |
( |
| ) |
const |
|
inline |
void hector_quadrotor_model::QuadrotorAerodynamics::reset |
( |
| ) |
|
void hector_quadrotor_model::QuadrotorAerodynamics::setBodyTwist |
( |
const geometry_msgs::Twist & |
twist | ) |
|
void hector_quadrotor_model::QuadrotorAerodynamics::setOrientation |
( |
const geometry_msgs::Quaternion & |
orientation | ) |
|
void hector_quadrotor_model::QuadrotorAerodynamics::setTwist |
( |
const geometry_msgs::Twist & |
twist | ) |
|
void hector_quadrotor_model::QuadrotorAerodynamics::setWind |
( |
const geometry_msgs::Vector3 & |
wind | ) |
|
void hector_quadrotor_model::QuadrotorAerodynamics::update |
( |
double |
dt | ) |
|
DragModel* hector_quadrotor_model::QuadrotorAerodynamics::drag_model_ |
|
private |
boost::mutex hector_quadrotor_model::QuadrotorAerodynamics::mutex_ |
|
private |
geometry_msgs::Quaternion hector_quadrotor_model::QuadrotorAerodynamics::orientation_ |
|
private |
geometry_msgs::Twist hector_quadrotor_model::QuadrotorAerodynamics::twist_ |
|
private |
geometry_msgs::Vector3 hector_quadrotor_model::QuadrotorAerodynamics::wind_ |
|
private |
geometry_msgs::Wrench hector_quadrotor_model::QuadrotorAerodynamics::wrench_ |
|
private |
The documentation for this class was generated from the following files: