Ignition Gazebo

API Reference

6.0.0~pre1
Conversions.hh File Reference
#include <ignition/msgs/actor.pb.h>
#include <ignition/msgs/atmosphere.pb.h>
#include <ignition/msgs/axis.pb.h>
#include <ignition/msgs/entity.pb.h>
#include <ignition/msgs/geometry.pb.h>
#include <ignition/msgs/gui.pb.h>
#include <ignition/msgs/inertial.pb.h>
#include <ignition/msgs/light.pb.h>
#include <ignition/msgs/material.pb.h>
#include <ignition/msgs/particle_emitter.pb.h>
#include <ignition/msgs/physics.pb.h>
#include <ignition/msgs/scene.pb.h>
#include <ignition/msgs/sensor.pb.h>
#include <ignition/msgs/sensor_noise.pb.h>
#include <ignition/msgs/time.pb.h>
#include <ignition/msgs/world_stats.pb.h>
#include <chrono>
#include <string>
#include <ignition/common/Console.hh>
#include <ignition/math/Inertial.hh>
#include <sdf/Actor.hh>
#include <sdf/Atmosphere.hh>
#include <sdf/Collision.hh>
#include <sdf/Geometry.hh>
#include <sdf/Gui.hh>
#include <sdf/JointAxis.hh>
#include <sdf/Light.hh>
#include <sdf/Material.hh>
#include <sdf/Noise.hh>
#include <sdf/ParticleEmitter.hh>
#include <sdf/Physics.hh>
#include <sdf/Scene.hh>
#include <sdf/Sensor.hh>
#include "ignition/gazebo/config.hh"
#include "ignition/gazebo/Export.hh"
#include "ignition/gazebo/Types.hh"

Go to the source code of this file.

Namespaces

 ignition
 This library is part of the Ignition Robotics project.
 
 ignition::gazebo
 Gazebo is a leading open source robotics simulator, that provides high fidelity physics, rendering, and sensor simulation.
 

Functions

template<class Out >
Out convert (const sdf::Geometry &_in)
 Generic conversion from an SDF geometry to another type. More...
 
template<>
msgs::Geometry convert (const sdf::Geometry &_in)
 Specialized conversion from an SDF geometry to a geometry message. More...
 
template<class Out >
Out convert (const msgs::Pose &_in)
 Generic conversion from a msgs Pose to another type. More...
 
template<>
math::Pose3d convert (const msgs::Pose &_in)
 Specialized conversion for msgs Pose to math Pose. More...
 
template<class Out >
Out convert (const msgs::Geometry &_in)
 Generic conversion from a geometry message to another type. More...
 
template<>
sdf::Geometry convert (const msgs::Geometry &_in)
 Specialized conversion from a geometry message to a geometry SDF object. More...
 
template<class Out >
Out convert (const sdf::Material &_in)
 Generic conversion from an SDF material to another type. More...
 
template<>
msgs::Material convert (const sdf::Material &_in)
 Specialized conversion from an SDF material to a material message. More...
 
template<class Out >
Out convert (const msgs::Material &_in)
 Generic conversion from a material message to another type. More...
 
template<>
sdf::Material convert (const msgs::Material &_in)
 Specialized conversion from a material message to a material SDF object. More...
 
template<class Out >
Out convert (const sdf::Actor &_in)
 Generic conversion from an SDF actor to another type. More...
 
template<>
msgs::Actor convert (const sdf::Actor &_in)
 Specialized conversion from an SDF actor to an actor message. More...
 
template<class Out >
Out convert (const msgs::Actor &_in)
 Generic conversion from an actor message to another type. More...
 
template<>
sdf::Actor convert (const msgs::Actor &_in)
 Specialized conversion from an actor message to an actor SDF object. More...
 
template<class Out >
Out convert (const sdf::Light &_in)
 Generic conversion from an SDF light to another type. More...
 
template<>
msgs::Light convert (const sdf::Light &_in)
 Specialized conversion from an SDF light to a light message. More...
 
std::string convert (const sdf::LightType &_in)
 Generic conversion from a SDF light type to string. More...
 
template<class Out >
Out convert (const msgs::Light &_in)
 Generic conversion from a light message to another type. More...
 
template<>
sdf::Light convert (const msgs::Light &_in)
 Specialized conversion from a light message to a light SDF object. More...
 
sdf::LightType convert (const std::string &_in)
 Specialized conversion from a string to a sdf light type. More...
 
template<class Out >
Out convert (const sdf::Gui &_in)
 Generic conversion from an SDF gui to another type. More...
 
template<>
msgs::GUI convert (const sdf::Gui &_in)
 Specialized conversion from an SDF gui to a gui message. More...
 
template<class Out >
Out convert (const std::chrono::steady_clock::duration &_in)
 Generic conversion from a steady clock duration to another type. More...
 
template<>
msgs::Time convert (const std::chrono::steady_clock::duration &_in)
 Specialized conversion from a steady clock duration to a time message. More...
 
template<class Out >
Out convert (const msgs::Time &_in)
 Generic conversion from a time message to another type. More...
 
template<>
std::chrono::steady_clock::duration convert (const msgs::Time &_in)
 Specialized conversion from a time message to a steady clock duration. More...
 
template<class Out >
Out convert (const math::Inertiald &_in)
 Generic conversion from a math inertial to another type. More...
 
template<>
msgs::Inertial convert (const math::Inertiald &_in)
 Specialized conversion from a math inertial to an inertial message. More...
 
template<class Out >
Out convert (const msgs::Inertial &_in)
 Generic conversion from an inertial message to another type. More...
 
template<>
math::Inertiald convert (const msgs::Inertial &_in)
 Specialized conversion from an inertial message to an inertial math object. More...
 
template<class Out >
Out convert (const sdf::JointAxis &_in)
 Generic conversion from an SDF joint axis to another type. More...
 
template<>
msgs::Axis convert (const sdf::JointAxis &_in)
 Specialized conversion from an SDF joint axis to an axis message. More...
 
template<class Out >
Out convert (const msgs::Axis &_in)
 Generic conversion from an axis message to another type. More...
 
template<>
sdf::JointAxis convert (const msgs::Axis &_in)
 Specialized conversion from an axis message to a joint axis SDF object. More...
 
template<class Out >
Out convert (const sdf::Scene &_in)
 Generic conversion from an SDF scene to another type. More...
 
template<>
msgs::Scene convert (const sdf::Scene &_in)
 Specialized conversion from an SDF scene to a scene message. More...
 
template<class Out >
Out convert (const msgs::Scene &_in)
 Generic conversion from a scene message to another type. More...
 
template<>
sdf::Scene convert (const msgs::Scene &_in)
 Specialized conversion from a scene message to a scene SDF object. More...
 
template<class Out >
Out convert (const sdf::Atmosphere &_in)
 Generic conversion from an SDF atmosphere to another type. More...
 
template<>
msgs::Atmosphere convert (const sdf::Atmosphere &_in)
 Specialized conversion from an SDF atmosphere to an atmosphere message. More...
 
template<class Out >
Out convert (const msgs::Atmosphere &_in)
 Generic conversion from an atmosphere message to another type. More...
 
template<>
sdf::Atmosphere convert (const msgs::Atmosphere &_in)
 Specialized conversion from an atmosphere message to an atmosphere SDF object. More...
 
template<class Out >
Out convert (const sdf::Physics &_in)
 Generic conversion from an SDF Physics to another type. More...
 
template<>
msgs::Physics convert (const sdf::Physics &_in)
 Specialized conversion from an SDF physics to a physics message. More...
 
template<class Out >
Out convert (const msgs::Physics &_in)
 Generic conversion from a physics message to another type. More...
 
template<>
sdf::Physics convert (const msgs::Physics &_in)
 Specialized conversion from a physics message to a physics SDF object. More...
 
template<class Out >
Out convert (const sdf::Sensor &_in)
 Generic conversion from an SDF Sensor to another type. More...
 
template<>
msgs::Sensor convert (const sdf::Sensor &_in)
 Specialized conversion from an SDF sensor to a sensor message. More...
 
template<class Out >
Out convert (const msgs::Sensor &_in)
 Generic conversion from a sensor message to another type. More...
 
template<>
sdf::Sensor convert (const msgs::Sensor &_in)
 Specialized conversion from a sensor message to a sensor SDF object. More...
 
template<class Out >
Out convert (const msgs::SensorNoise &_in)
 Generic conversion from a sensor noise message to another type. More...
 
template<>
sdf::Noise convert (const msgs::SensorNoise &_in)
 Specialized conversion from a sensor noise message to a noise SDF object. More...
 
template<class Out >
Out convert (const msgs::WorldStatistics &_in)
 Generic conversion from a world statistics message to another type. More...
 
template<>
UpdateInfo convert (const msgs::WorldStatistics &_in)
 Specialized conversion from a world statistics message to an UpdateInfo object. More...
 
template<class Out >
Out convert (const UpdateInfo &_in)
 Generic conversion from update info to another type. More...
 
template<>
msgs::WorldStatistics convert (const UpdateInfo &_in)
 Specialized conversion from update info to a world statistics message. More...
 
template<class Out >
Out convert (const sdf::Collision &_in)
 Generic conversion from an SDF collision to another type. More...
 
template<>
msgs::Collision convert (const sdf::Collision &_in)
 Specialized conversion from an SDF collision to a collision message. More...
 
template<class Out >
Out convert (const msgs::Collision &_in)
 Generic conversion from a collision message to another type. More...
 
template<>
sdf::Collision convert (const msgs::Collision &_in)
 Specialized conversion from a collision message to a collision SDF object. More...
 
template<class Out >
Out convert (const math::AxisAlignedBox &_in)
 Generic conversion from axis aligned box object to another type. More...
 
template<>
msgs::AxisAlignedBox convert (const math::AxisAlignedBox &_in)
 Specialized conversion from a math axis aligned box object to an axis aligned box message. More...
 
template<class Out >
Out convert (const msgs::AxisAlignedBox &_in)
 Generic conversion from an axis aligned box message to another type. More...
 
template<>
math::AxisAlignedBox convert (const msgs::AxisAlignedBox &_in)
 Specialized conversion from an math axis aligned box message to an axis aligned box object. More...
 
template<class Out >
Out convert (const sdf::ParticleEmitter &)
 Generic conversion from a particle emitter SDF object to another type. More...
 
template<>
msgs::ParticleEmitter convert (const sdf::ParticleEmitter &_in)
 Specialized conversion from a particle emitter SDF object to a particle emitter message object. More...
 
template<class Out >
Out convert (const msgs::ParticleEmitter &)
 Generic conversion from a particle emitter SDF object to another type. More...
 
template<>
sdf::ParticleEmitter convert (const msgs::ParticleEmitter &_in)
 Specialized conversion from a particle emitter SDF object to a particle emitter message object. More...
 
void set (msgs::SensorNoise *_msg, const sdf::Noise &_sdf)
 Helper function that sets a mutable msgs::SensorNoise object to the values contained in a sdf::Noise object. More...
 
void set (msgs::WorldStatistics *_msg, const UpdateInfo &_in)
 Helper function that sets a mutable msgs::WorldStatistics object to the values contained in a gazebo::UpdateInfo object. More...
 
void set (msgs::Time *_msg, const std::chrono::steady_clock::duration &_in)
 Helper function that sets a mutable msgs::Time object to the values contained in a std::chrono::steady_clock::duration object. More...