Common.hh
uint64_t Entity
An Entity identifies a single object in simulation such as a model, link, or light....
Definition: gz/sim/Entity.hh:59
This library is part of the Ignition Robotics project.
The EntityComponentManager constructs, deletes, and returns components and entities....
Definition: gz/sim/EntityComponentManager.hh:65
Noise parameters used when computing frame data. These are all assumed to be gaussian.
Definition: Parameters.hh:84
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 i...
Definition: Common.hh:109
Struct containing linear and angular velocities.
Definition: Common.hh:44
std::optional< Eigen::Matrix4Xd > calculateAllocationMatrix(const RotorConfiguration &_rotorConfiguration)
Create the matrix that maps rotor velocities to thrust and moments.
This class provides wrappers around entities and components which are more convenient and straight-fo...
Definition: gz/sim/Model.hh:60
Eigen::Vector3d linear
Definition: Common.hh:46
RotorConfiguration loadRotorConfiguration(const EntityComponentManager &_ecm, const sdf::ElementPtr &_sdf, const Model &_model, const Entity &_comLink)
Loads rotor configuration from SDF.
Frame data of a link including its pose and linear velocity in world frame as well as its angular vel...
Definition: Common.hh:52
Eigen::Vector3d angular
Definition: Common.hh:47
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.
Definition: Common.hh:97
Eigen::Vector3d angularVelocityBody
Definition: Common.hh:58
Eigen::Vector3d linearVelocityWorld
Definition: Common.hh:57
void createFrameDataComponents(EntityComponentManager &_ecm, const Entity &_link)
Creates components necessary for obtaining the frame data of the given link.
Eigen::Isometry3d pose
Definition: Common.hh:56
std::optional< FrameData > getFrameData(const EntityComponentManager &_ecm, const Entity &_link, const NoiseParameters &_noise)
Retrieves the frame data of the given link and applies noise.