Classes | |
struct | EigenTwist |
Struct containing linear and angular velocities. More... | |
struct | FrameData |
Frame data of a link including its pose and linear velocity in world frame as well as its angular velocity in body frame. More... | |
class | LeeVelocityController |
struct | LeeVelocityControllerParameters |
Data structure containing various parameters for the Lee velocity controller. More... | |
struct | NoiseParameters |
Noise parameters used when computing frame data. These are all assumed to be gaussian. More... | |
struct | Rotor |
A struct that holds various properties of a rotor. More... | |
struct | VehicleParameters |
A struct that holds properties of the vehicle such as mass, inertia and rotor configuration. Gravity is also included even though it's not a parameter unique to the vehicle. More... | |
Typedefs | |
using | RotorConfiguration = std::vector< Rotor > |
A collection of Rotor objects. More... | |
Functions | |
std::optional< Eigen::Matrix4Xd > | calculateAllocationMatrix (const RotorConfiguration &_rotorConfiguration) |
Create the matrix that maps rotor velocities to thrust and moments. More... | |
void | createFrameDataComponents (EntityComponentManager &_ecm, const Entity &_link) |
Creates components necessary for obtaining the frame data of the given link. More... | |
std::optional< FrameData > | getFrameData (const EntityComponentManager &_ecm, const Entity &_link, const NoiseParameters &_noise) |
Retrieves the frame data of the given link and applies noise. More... | |
RotorConfiguration | loadRotorConfiguration (const EntityComponentManager &_ecm, const sdf::ElementPtr &_sdf, const Model &_model, const Entity &_comLink) |
Loads rotor configuration from SDF. More... | |
Eigen::Matrix3d | skewMatrixFromVector (const Eigen::Vector3d &_vector) |
Creates a skew symmetric matrix (so(3)) from a vector. This is sometimes referred to as the hat map. More... | |
Eigen::Vector3d | vectorFromSkewMatrix (const Eigen::Matrix3d &_skewMatrix) |
Creates a vector from a skew symmetric matrix(so3). This is sometimes referred to as the vee map or inverse hat map. More... | |
Typedef Documentation
◆ RotorConfiguration
using RotorConfiguration = std::vector<Rotor> |
A collection of Rotor objects.
Function Documentation
◆ calculateAllocationMatrix()
std::optional<Eigen::Matrix4Xd> ignition::gazebo::systems::multicopter_control::calculateAllocationMatrix | ( | const RotorConfiguration & | _rotorConfiguration | ) |
Create the matrix that maps rotor velocities to thrust and moments.
- Parameters
-
[in] _rotorConfiguration Rotor configurations
- Returns
- nullopt if the rotor configuration results in uncontrollable system. Otherwise, returns the computed matrix.
◆ createFrameDataComponents()
void ignition::gazebo::systems::multicopter_control::createFrameDataComponents | ( | EntityComponentManager & | _ecm, |
const Entity & | _link | ||
) |
Creates components necessary for obtaining the frame data of the given link.
- Parameters
-
[in] _ecm Mutable reference to the entity component manager [in] _link Link on which the components will be created.
◆ getFrameData()
std::optional<FrameData> ignition::gazebo::systems::multicopter_control::getFrameData | ( | const EntityComponentManager & | _ecm, |
const Entity & | _link, | ||
const NoiseParameters & | _noise | ||
) |
Retrieves the frame data of the given link and applies noise.
- Parameters
-
[in] _ecm Imutable reference to the entity component manager [in] _link Link on which the components will be created. [in] _noise Noise parameters
◆ loadRotorConfiguration()
RotorConfiguration ignition::gazebo::systems::multicopter_control::loadRotorConfiguration | ( | const EntityComponentManager & | _ecm, |
const sdf::ElementPtr & | _sdf, | ||
const Model & | _model, | ||
const Entity & | _comLink | ||
) |
◆ skewMatrixFromVector()
|
inline |
Creates a skew symmetric matrix (so(3)) from a vector. This is sometimes referred to as the hat map.
- Parameters
-
[in] _vector any vector in R3
- Returns
- a skew symmetric matrix in so(3)
◆ vectorFromSkewMatrix()
|
inline |
Creates a vector from a skew symmetric matrix(so3). This is sometimes referred to as the vee map or inverse hat map.
- Parameters
-
[in] _skewMatrix any matrix in so(3)
- Returns
- a vector in R3