Classes | |
class | Factory |
A factory that generates protobuf message based on a string type. This allows for global registration of messages via static initialization. If you don't need the singleton, consider using MessageFactory instead. More... | |
class | MessageFactory |
A factory that generates protobuf message based on a string type. This class will also try to load all Protobuf descriptors in paths provided in LoadDescriptors as well as the GZ_DESCRIPTOR_PATH environment variable. More... | |
class | PointCloudPackedConstIterator |
Same as a PointCloudPackedIterator but for const data. More... | |
class | PointCloudPackedIterator |
Class that can iterate over a PointCloudPacked message. More... | |
Functions | |
gz::math::AxisAlignedBox | Convert (const AxisAlignedBox &_msg) |
Boolean | Convert (const bool &_data) |
bool | Convert (const Boolean &_msg) |
gz::math::Color | Convert (const Color &_msg) |
Double | Convert (const double &_data) |
double | Convert (const Double &_msg) |
Float | Convert (const float &_data) |
float | Convert (const Float &_msg) |
AxisAlignedBox | Convert (const gz::math::AxisAlignedBox &_data) |
Color | Convert (const gz::math::Color &_data) |
Inertial | Convert (const gz::math::Inertiald &_data) |
Inertial | Convert (const gz::math::MassMatrix3d &_data) |
PlaneGeom | Convert (const gz::math::Planed &_data) |
Pose | Convert (const gz::math::Pose3d &_data) |
Quaternion | Convert (const gz::math::Quaterniond &_data) |
SphericalCoordinates | Convert (const gz::math::SphericalCoordinates &_data) |
Vector2d | Convert (const gz::math::Vector2d &_data) |
Vector3d | Convert (const gz::math::Vector3d &_data) |
gz::math::Inertiald | Convert (const Inertial &_msg) |
int32_t | Convert (const Int32 &_msg) |
Int32 | Convert (const int32_t &_data) |
int64_t | Convert (const Int64 &_msg) |
Int64 | Convert (const int64_t &_data) |
math::SphericalCoordinates::CoordinateType | Convert (const msgs::SphericalCoordinatesType &_sc) |
gz::math::Planed | Convert (const PlaneGeom &_msg) |
gz::math::Pose3d | Convert (const Pose &_msg) |
gz::math::Quaterniond | Convert (const Quaternion &_msg) |
gz::math::SphericalCoordinates | Convert (const SphericalCoordinates &_msg) |
Time | Convert (const std::chrono::steady_clock::duration &_data) |
StringMsg | Convert (const std::string &_data) |
std::string | Convert (const StringMsg &_msg) |
std::chrono::steady_clock::duration | Convert (const Time &_msg) |
uint32_t | Convert (const UInt32 &_msg) |
UInt32 | Convert (const uint32_t &_data) |
uint64_t | Convert (const UInt64 &_msg) |
UInt64 | Convert (const uint64_t &_data) |
gz::math::Vector2d | Convert (const Vector2d &_msg) |
gz::math::Vector3d | Convert (const Vector3d &_msg) |
msgs::SphericalCoordinatesType | ConvertCoord (const math::SphericalCoordinates::CoordinateType &_sc) |
std::string | ConvertDiscoveryType (const msgs::Discovery::Type &_type) |
msgs::Discovery::Type | ConvertDiscoveryType (const std::string &_str) |
bool | ConvertFuelMetadata (const msgs::FuelMetadata &_meta, std::string &_modelConfigStr) |
bool | ConvertFuelMetadata (const std::string &_modelConfigStr, msgs::FuelMetadata &_meta) |
std::string | ConvertGeometryType (const msgs::Geometry::Type _type) |
msgs::Geometry::Type | ConvertGeometryType (const std::string &_str) |
std::string | ConvertJointType (const msgs::Joint::Type &_type) |
msgs::Joint::Type | ConvertJointType (const std::string &_str) |
std::string | ConvertPixelFormatType (const msgs::PixelFormatType &_t) |
msgs::PixelFormatType | ConvertPixelFormatType (const std::string &_str) |
std::string | ConvertShaderType (const msgs::Material::ShaderType &_type) |
msgs::Material::ShaderType | ConvertShaderType (const std::string &_str) |
std::string | getInstallPrefix () |
getInstallPrefix return the install prefix of the library i.e. CMAKE_INSTALL_PREFIX unless the library has been moved More... | |
void | InitPointCloudPacked (msgs::PointCloudPacked &_msg, const std::string &_frameId, bool _memoryAligned, const std::vector< std::pair< std::string, msgs::PointCloudPacked::Field::DataType >> &_fields) |
void | Set (AxisAlignedBox *_msg, const gz::math::AxisAlignedBox &_data) |
void | Set (bool *_data, const Boolean &_msg) |
void | Set (Boolean *_msg, const bool &_data) |
void | Set (Color *_msg, const gz::math::Color &_data) |
void | Set (double *_data, const Double &_msg) |
void | Set (Double *_msg, const double &_data) |
void | Set (float *_data, const Float &_msg) |
void | Set (Float *_msg, const float &_data) |
void | Set (gz::math::AxisAlignedBox *_data, const AxisAlignedBox &_msg) |
void | Set (gz::math::Color *_data, const Color &_msg) |
void | Set (gz::math::Inertiald *_data, const Inertial &_msg) |
void | Set (gz::math::MassMatrix3d *_data, const Inertial &_msg) |
void | Set (gz::math::Planed *_data, const PlaneGeom &_msg) |
void | Set (gz::math::Pose3d *_data, const Pose &_msg) |
void | Set (gz::math::Quaterniond *_data, const Quaternion &_msg) |
void | Set (gz::math::SphericalCoordinates *_data, const SphericalCoordinates &_msg) |
void | Set (gz::math::Vector2d *_data, const Vector2d &_msg) |
void | Set (gz::math::Vector3d *_data, const Vector3d &_msg) |
void | Set (Inertial *_msg, const gz::math::Inertiald &_data) |
void | Set (Inertial *_msg, const gz::math::MassMatrix3d &_data) |
void | Set (Int32 *_msg, const int32_t &_data) |
void | Set (int32_t *_data, const Int32 &_msg) |
void | Set (Int64 *_msg, const int64_t &_data) |
void | Set (int64_t *_data, const Int64 &_msg) |
void | Set (PlaneGeom *_msg, const gz::math::Planed &_data) |
void | Set (Pose *_msg, const gz::math::Pose3d &_data) |
void | Set (Quaternion *_msg, const gz::math::Quaterniond &_data) |
void | Set (SphericalCoordinates *_msg, const gz::math::SphericalCoordinates &_data) |
void | Set (std::chrono::steady_clock::duration *_data, const Time &_msg) |
void | Set (std::string *_data, const StringMsg &_msg) |
void | Set (StringMsg *_msg, const char *_data) |
void | Set (StringMsg *_msg, const std::string &_data) |
void | Set (Time *_msg, const std::chrono::steady_clock::duration &_data) |
void | Set (UInt32 *_msg, const uint32_t &_data) |
void | Set (uint32_t *_data, const UInt32 &_msg) |
void | Set (UInt64 *_msg, const uint64_t &_data) |
void | Set (uint64_t *_data, const UInt64 &_msg) |
void | Set (Vector2d *_msg, const gz::math::Vector2d &_data) |
void | Set (Vector3d *_msg, const gz::math::Vector3d &_data) |
int | sizeOfPointField (PointCloudPacked::Field::DataType _dataType) |
Return the size of a datatype (which is an enum of PointCloudPacked::Field) in bytes. More... | |
std::string | ToString (const msgs::Discovery::Type &_t) |
Function Documentation
◆ Convert() [1/38]
|
inline |
References Set().
◆ Convert() [2/38]
|
inline |
References Set().
◆ Convert() [3/38]
|
inline |
References Set().
◆ Convert() [4/38]
|
inline |
References Set().
◆ Convert() [5/38]
|
inline |
References Set().
◆ Convert() [6/38]
|
inline |
References Set().
◆ Convert() [7/38]
|
inline |
References Set().
◆ Convert() [8/38]
|
inline |
References Set().
◆ Convert() [9/38]
|
inline |
◆ Convert() [10/38]
|
inline |
References Set().
◆ Convert() [11/38]
|
inline |
References Set().
◆ Convert() [12/38]
|
inline |
References Set().
◆ Convert() [13/38]
|
inline |
References Set().
◆ Convert() [14/38]
|
inline |
References Set().
◆ Convert() [15/38]
|
inline |
References Set().
◆ Convert() [16/38]
|
inline |
References Set().
◆ Convert() [17/38]
|
inline |
References Set().
◆ Convert() [18/38]
|
inline |
References Set().
◆ Convert() [19/38]
|
inline |
References Set().
◆ Convert() [20/38]
|
inline |
References Set().
◆ Convert() [21/38]
|
inline |
References Set().
◆ Convert() [22/38]
|
inline |
References Set().
◆ Convert() [23/38]
|
inline |
References Set().
◆ Convert() [24/38]
|
inline |
References std::endl().
◆ Convert() [25/38]
|
inline |
References Set().
◆ Convert() [26/38]
|
inline |
References Set().
◆ Convert() [27/38]
|
inline |
References Set().
◆ Convert() [28/38]
|
inline |
References Set().
◆ Convert() [29/38]
|
inline |
References Set().
◆ Convert() [30/38]
|
inline |
References Set().
◆ Convert() [31/38]
|
inline |
References Set().
◆ Convert() [32/38]
|
inline |
References Set().
◆ Convert() [33/38]
|
inline |
References Set().
◆ Convert() [34/38]
|
inline |
References Set().
◆ Convert() [35/38]
|
inline |
References Set().
◆ Convert() [36/38]
|
inline |
References Set().
◆ Convert() [37/38]
|
inline |
References Set().
◆ Convert() [38/38]
|
inline |
References Set().
◆ ConvertCoord()
|
inline |
References std::endl().
◆ ConvertDiscoveryType() [1/2]
|
inline |
◆ ConvertDiscoveryType() [2/2]
|
inline |
References std::endl().
Referenced by ToString().
◆ ConvertFuelMetadata() [1/2]
|
inline |
References ostringstream::str().
◆ ConvertFuelMetadata() [2/2]
|
inline |
◆ ConvertGeometryType() [1/2]
|
inline |
References std::endl().
◆ ConvertGeometryType() [2/2]
|
inline |
References std::endl().
◆ ConvertJointType() [1/2]
|
inline |
References std::endl().
◆ ConvertJointType() [2/2]
|
inline |
References std::endl().
◆ ConvertPixelFormatType() [1/2]
|
inline |
◆ ConvertPixelFormatType() [2/2]
|
inline |
◆ ConvertShaderType() [1/2]
|
inline |
References std::endl().
◆ ConvertShaderType() [2/2]
|
inline |
References std::endl().
◆ getInstallPrefix()
std::string gz::msgs::getInstallPrefix | ( | ) |
getInstallPrefix return the install prefix of the library i.e. CMAKE_INSTALL_PREFIX unless the library has been moved
◆ InitPointCloudPacked()
|
inline |
References gz::math::roundUpMultiple().
◆ Set() [1/39]
|
inline |
References AxisAlignedBox::Max(), and AxisAlignedBox::Min().
◆ Set() [2/39]
|
inline |
◆ Set() [3/39]
|
inline |
◆ Set() [4/39]
|
inline |
References Color::A(), Color::B(), Color::G(), and Color::R().
◆ Set() [5/39]
|
inline |
◆ Set() [6/39]
|
inline |
◆ Set() [7/39]
|
inline |
◆ Set() [8/39]
|
inline |
◆ Set() [9/39]
|
inline |
References AxisAlignedBox::Max(), AxisAlignedBox::Min(), and Set().
◆ Set() [10/39]
|
inline |
References Color::Set().
◆ Set() [11/39]
|
inline |
◆ Set() [12/39]
|
inline |
◆ Set() [13/39]
|
inline |
References Convert(), and Plane< class >::Set().
◆ Set() [14/39]
|
inline |
References Convert(), and Pose3< class >::Set().
◆ Set() [15/39]
|
inline |
References Quaternion< class >::Set().
◆ Set() [16/39]
|
inline |
References SphericalCoordinates::CUSTOM_SURFACE, SphericalCoordinates::EARTH_WGS84, std::endl(), SphericalCoordinates::MOON_SCS, SphericalCoordinates::SetElevationReference(), SphericalCoordinates::SetHeadingOffset(), SphericalCoordinates::SetLatitudeReference(), SphericalCoordinates::SetLongitudeReference(), and SphericalCoordinates::SetSurface().
◆ Set() [17/39]
|
inline |
References Vector2< class >::Set().
◆ Set() [18/39]
|
inline |
References Vector3< class >::Set().
◆ Set() [19/39]
|
inline |
◆ Set() [20/39]
|
inline |
◆ Set() [21/39]
|
inline |
◆ Set() [22/39]
|
inline |
◆ Set() [23/39]
|
inline |
◆ Set() [24/39]
|
inline |
◆ Set() [25/39]
|
inline |
References Plane< class >::Normal(), Plane< class >::Offset(), Set(), and Plane< class >::Size().
◆ Set() [26/39]
|
inline |
References Pose3< class >::Pos(), Pose3< class >::Rot(), and Set().
◆ Set() [27/39]
|
inline |
◆ Set() [28/39]
|
inline |
References SphericalCoordinates::CUSTOM_SURFACE, Angle::Degree(), SphericalCoordinates::EARTH_WGS84, SphericalCoordinates::ElevationReference(), std::endl(), SphericalCoordinates::HeadingOffset(), SphericalCoordinates::LatitudeReference(), SphericalCoordinates::LongitudeReference(), SphericalCoordinates::MOON_SCS, SphericalCoordinates::Surface(), SphericalCoordinates::SurfaceAxisEquatorial(), and SphericalCoordinates::SurfaceAxisPolar().
◆ Set() [29/39]
|
inline |
◆ Set() [30/39]
|
inline |
References string::data().
◆ Set() [31/39]
|
inline |
◆ Set() [32/39]
|
inline |
◆ Set() [33/39]
|
inline |
References gz::math::durationToSecNsec().
◆ Set() [34/39]
|
inline |
◆ Set() [35/39]
|
inline |
◆ Set() [36/39]
|
inline |
◆ Set() [37/39]
|
inline |
◆ Set() [38/39]
|
inline |
References Vector2< class >::X(), and Vector2< class >::Y().
◆ Set() [39/39]
|
inline |
References Vector3< class >::X(), Vector3< class >::Y(), and Vector3< class >::Z().
◆ sizeOfPointField()
|
inline |
Return the size of a datatype (which is an enum of PointCloudPacked::Field) in bytes.
- Parameters
-
[in] _dataType One of the enums of PointCloudPacked::Field
- Returns
- Size in bytes. Returns -1 if the type is unknown.
References std::endl().
◆ ToString()
|
inline |
References ConvertDiscoveryType().