#include <Eigen/Dense>
#include <yaml-cpp/yaml.h>
Go to the source code of this file.
Classes | |
struct | gazebo::ControlSurface |
struct | gazebo::FWAerodynamicParameters |
struct | gazebo::FWVehicleParameters |
Namespaces | |
namespace | gazebo |
Defines | |
#define | READ_CONTROL_SURFACE(node, item) YAMLReadControlSurface(node, #item, item); |
Macros to reduce copies of names. | |
#define | READ_EIGEN_VECTOR(node, item) YAMLReadEigenVector(node, #item, item); |
#define | READ_PARAM(node, item) YAMLReadParam(node, #item, item); |
Functions | |
void | gazebo::YAMLReadControlSurface (const YAML::Node &node, const std::string &name, ControlSurface &surface) |
Wrapper function for extracting control surface parameters from a YAML node. | |
template<typename Derived > | |
void | gazebo::YAMLReadEigenVector (const YAML::Node &node, const std::string &name, Eigen::MatrixBase< Derived > &value) |
This function reads a vector from a YAML node and converts it into a vector of type Eigen. | |
template<typename T > | |
void | gazebo::YAMLReadParam (const YAML::Node &node, const std::string &name, T &value) |
This function reads a parameter from a YAML node. | |
Variables | |
static constexpr int | gazebo::kDefaultAileronLeftChannel = 4 |
static constexpr int | gazebo::kDefaultAileronRightChannel = 0 |
static constexpr double | gazebo::kDefaultAlphaMax = 0.27 |
static constexpr double | gazebo::kDefaultAlphaMin = -0.27 |
static const Eigen::Vector3d | gazebo::kDefaultCDragAlpha |
static const Eigen::Vector3d | gazebo::kDefaultCDragBeta |
static const Eigen::Vector3d | gazebo::kDefaultCDragDeltaAil |
static const Eigen::Vector3d | gazebo::kDefaultCDragDeltaFlp |
static constexpr double | gazebo::kDefaultChordLength = 0.18 |
static const Eigen::Vector4d | gazebo::kDefaultCLiftAlpha |
static const Eigen::Vector2d | gazebo::kDefaultCLiftDeltaAil |
static const Eigen::Vector2d | gazebo::kDefaultCLiftDeltaFlp |
static constexpr double | gazebo::kDefaultControlSurfaceDeflectionMax |
static constexpr double | gazebo::kDefaultControlSurfaceDeflectionMin |
static const Eigen::Vector2d | gazebo::kDefaultCPitchMomentAlpha |
static const Eigen::Vector2d | gazebo::kDefaultCPitchMomentDeltaElv |
static const Eigen::Vector2d | gazebo::kDefaultCPitchMomentQ |
static const Eigen::Vector2d | gazebo::kDefaultCRollMomentBeta |
static const Eigen::Vector2d | gazebo::kDefaultCRollMomentDeltaAil |
static const Eigen::Vector2d | gazebo::kDefaultCRollMomentDeltaFlp |
static const Eigen::Vector2d | gazebo::kDefaultCRollMomentP |
static const Eigen::Vector2d | gazebo::kDefaultCRollMomentR |
static const Eigen::Vector2d | gazebo::kDefaultCSideForceBeta |
static const Eigen::Vector3d | gazebo::kDefaultCThrust |
static const Eigen::Vector2d | gazebo::kDefaultCYawMomentBeta |
static const Eigen::Vector2d | gazebo::kDefaultCYawMomentDeltaRud |
static const Eigen::Vector2d | gazebo::kDefaultCYawMomentR |
static constexpr int | gazebo::kDefaultElevatorChannel = 1 |
static constexpr int | gazebo::kDefaultFlapChannel = 2 |
static constexpr int | gazebo::kDefaultRudderChannel = 3 |
static constexpr int | gazebo::kDefaultThrottleChannel = 5 |
static constexpr double | gazebo::kDefaultThrustInclination = 0.0 |
static constexpr double | gazebo::kDefaultWingSpan = 2.59 |
static constexpr double | gazebo::kDefaultWingSurface = 0.47 |
#define READ_CONTROL_SURFACE | ( | node, | |
item | |||
) | YAMLReadControlSurface(node, #item, item); |
Macros to reduce copies of names.
Definition at line 118 of file fw_parameters.h.
#define READ_EIGEN_VECTOR | ( | node, | |
item | |||
) | YAMLReadEigenVector(node, #item, item); |
Definition at line 120 of file fw_parameters.h.
#define READ_PARAM | ( | node, | |
item | |||
) | YAMLReadParam(node, #item, item); |
Definition at line 121 of file fw_parameters.h.