Crate sdformat

Crate sdformat 

Source

Re-exports§

pub use yaserde;

Structs§

Boxed
ElementMap
Pose
Simple implementation of pose
SdfActor
A unique name for the actor.
SdfActorAnimation
Unique name for animation.
SdfActorScript
Adds scripted trajectories to the actor.
SdfActorScriptTrajectory
The tension of the trajectory spline. The default value of zero equates to a Catmull-Rom spline, which may also cause the animation to overshoot keyframes. A value of one will cause the animation to stick to the keyframes.
SdfActorScriptTrajectoryWaypoint
Each point in the trajectory.
SdfActorSkin
Skin file which defines a visual and the underlying skeleton which moves it.
SdfAirPressure
These elements are specific to an air pressure sensor.
SdfAirPressurePressure
Noise parameters for the pressure data.
SdfAltimeter
These elements are specific to an altimeter sensor.
SdfAltimeterVerticalPosition
Noise parameters for vertical position
SdfAltimeterVerticalVelocity
Noise parameters for vertical velocity
SdfAtmosphere
The type of the atmosphere engine. Current options are adiabatic. Defaults to adiabatic if left unspecified.
SdfAudioSink
An audio sink.
SdfAudioSource
An audio source.
SdfAudioSourceContact
List of collision objects that will trigger audio playback.
SdfBattery
Unique name for the battery.
SdfBoxShape
Box shape
SdfCamera
An optional name for the camera.
SdfCameraClip
The near and far clip planes. Objects closer or farther than these planes are not rendered.
SdfCameraDepthCamera
Depth camera parameters
SdfCameraDepthCameraClip
The near and far clip planes. Objects closer or farther than these planes are not detected by the depth camera.
SdfCameraDistortion
Lens distortion to be applied to camera images. See http://en.wikipedia.org/wiki/Distortion_(optics)#Software_correction
SdfCameraImage
The image size in pixels and format.
SdfCameraLens
Lens projection description
SdfCameraLensCustomFunction
Definition of custom mapping function in a form of r=c1ffun(theta/c2 + c3). See https://en.wikipedia.org/wiki/Fisheye_lens#Mapping_function
SdfCameraLensIntrinsics
Camera intrinsic parameters for setting a custom perspective projection matrix (cannot be used with WideAngleCamera since this class uses image stitching from 6 different cameras for achieving a wide field of view). The focal lengths can be computed using focal_length_in_pixels = (image_width_in_pixels * 0.5) / tan(field_of_view_in_degrees * 0.5 * PI/180)
SdfCameraLensProjection
Camera projection matrix P for overriding camera intrinsic matrix K values so that users can configure P independently of K. This is useful when working with stereo cameras where P may be different from K due to the transform between the two cameras.
SdfCameraNoise
The properties of the noise model that should be applied to generated images
SdfCameraSave
True = saving enabled
SdfCapsuleShape
Capsule shape
SdfCollision
Unique name for the collision element within the scope of the parent link.
SdfContact
These elements are specific to the contact sensor.
SdfCylinderShape
Cylinder shape
SdfEllipsoidShape
Ellipsoid shape
SdfForcetorque
These elements are specific to the force torque sensor.
SdfForcetorqueForce
These elements are specific to measurement-frame force, which is expressed in Newtons
SdfForcetorqueForceX
Force along the X axis
SdfForcetorqueForceY
Force along the Y axis
SdfForcetorqueForceZ
Force along the Z axis
SdfForcetorqueTorque
These elements are specific to measurement-frame torque, which is expressed in Newton-meters
SdfForcetorqueTorqueX
Torque about the X axis
SdfForcetorqueTorqueY
Force about the Y axis
SdfForcetorqueTorqueZ
Torque about the Z axis
SdfFrame
SdfGps
These elements are specific to the GPS sensor.
SdfGpsPositionSensing
Parameters related to GPS position measurement.
SdfGpsPositionSensingHorizontal
Noise parameters for horizontal position measurement, in units of meters.
SdfGpsPositionSensingVertical
Noise parameters for vertical position measurement, in units of meters.
SdfGpsVelocitySensing
Parameters related to GPS position measurement.
SdfGpsVelocitySensingHorizontal
Noise parameters for horizontal velocity measurement, in units of meters/second.
SdfGpsVelocitySensingVertical
Noise parameters for vertical velocity measurement, in units of meters/second.
SdfGripper
SdfGripperGraspCheck
SdfGui
SdfGuiCamera
SdfGuiCameraTrackVisual
SdfHeightmapShape
A heightmap based on a 2d grayscale image.
SdfHeightmapShapeBlend
The blend tag controls how two adjacent textures are mixed. The number of blend elements should equal one less than the number of textures.
SdfHeightmapShapeTexture
The heightmap can contain multiple textures. The order of the texture matters. The first texture will appear at the lowest height, and the last texture at the highest height. Use blend to control the height thresholds and fade between textures.
SdfImageShape
Extrude a set of boxes from a grayscale image.
SdfImu
These elements are specific to the IMU sensor.
SdfImuAngularVelocity
These elements are specific to body-frame angular velocity, which is expressed in radians per second
SdfImuAngularVelocityX
Angular velocity about the X axis
SdfImuAngularVelocityY
Angular velocity about the Y axis
SdfImuAngularVelocityZ
Angular velocity about the Z axis
SdfImuLinearAcceleration
These elements are specific to body-frame linear acceleration, which is expressed in meters per second squared
SdfImuLinearAccelerationX
Linear acceleration about the X axis
SdfImuLinearAccelerationY
Linear acceleration about the Y axis
SdfImuLinearAccelerationZ
Linear acceleration about the Z axis
SdfImuOrientationReferenceFrame
SdfInertial
The link’s mass, position of its center of mass, its central inertia properties, and optionally its fluid added mass.
SdfInertialFluidAddedMass
This link’s fluid added mass matrix about the link’s origin. This matrix represents the inertia of the fluid that is dislocated when the body moves. Added mass should be zero if the density of the surrounding fluid is negligible with respect to the body’s density. The 6x6 matrix is symmetric, therefore only 21 unique elements can be set. The elements of the matrix follow the [x, y, z, p, q, r] notation, where [x, y, z] correspond to translation and [p, q, r] to rotation (i.e. roll, pitch, yaw).
SdfInertialInertia
This link’s moments of inertia ixx, iyy, izz and products of inertia ixy, ixz, iyz about Co (the link’s center of mass) for the unit vectors Ĉx, Ĉy, Ĉᴢ fixed in the center-of-mass-frame C. Note: the orientation of Ĉx, Ĉy, Ĉᴢ relative to L̂x, L̂y, L̂ᴢ is specified by the pose tag. To avoid compatibility issues associated with the negative sign convention for product of inertia, align Ĉx, Ĉy, Ĉᴢ with principal inertia directions so that all the products of inertia are zero. For more information about this sign convention, see the following MathWorks documentation for working with CAD tools: https://www.mathworks.com/help/releases/R2021b/physmod/sm/ug/specify-custom-inertia.html#mw_b043ec69-835b-4ca9-8769-af2e6f1b190c
SdfJoint
The type of joint, which must be one of the following: (continuous) a hinge joint that rotates on a single axis with a continuous range of motion, (revolute) a hinge joint that rotates on a single axis with a fixed range of motion, (gearbox) geared revolute joints, (revolute2) same as two revolute joints connected in series, (prismatic) a sliding joint that slides along an axis with a limited range specified by upper and lower limits, (ball) a ball and socket joint, (screw) a single degree of freedom joint with coupled sliding and rotational motion, (universal) like a ball joint, but constrains one degree of freedom, (fixed) a joint with zero degrees of freedom that rigidly connects two links.
SdfJointAxis
Parameters related to the axis of rotation for revolute joints, the axis of translation for prismatic joints.
SdfJointAxis2
Parameters related to the second axis of rotation for revolute2 joints and universal joints.
SdfJointAxis2Dynamics
An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation.
SdfJointAxis2Limit
SdfJointAxisDynamics
An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation.
SdfJointAxisLimit
specifies the limits of this joint
SdfJointPhysics
Parameters that are specific to a certain physics engine.
SdfJointPhysicsOde
ODE specific parameters
SdfJointPhysicsOdeLimit
SdfJointPhysicsOdeSuspension
SdfJointPhysicsSimbody
Simbody specific parameters
SdfLidar
These elements are specific to the lidar sensor.
SdfLidarNoise
The properties of the noise model that should be applied to generated scans
SdfLidarRange
specifies range properties of each simulated lidar
SdfLidarScan
SdfLidarScanHorizontal
SdfLidarScanVertical
SdfLight
The light type: point, directional, spot.
SdfLightAttenuation
Light attenuation
SdfLightSpot
Spot light parameters
SdfLightState
Name of the light
SdfLink
A unique name for the link within the scope of the model.
SdfLinkState
Name of the link
SdfLinkStateCollision
Name of the collision
SdfLinkVelocityDecay
Exponential damping of the link’s velocity.
SdfLogicalCamera
These elements are specific to logical camera sensors. A logical camera reports objects that fall within a frustum. Computation should be performed on the CPU.
SdfMagnetometer
These elements are specific to a Magnetometer sensor.
SdfMagnetometerX
Parameters related to the body-frame X axis of the magnetometer
SdfMagnetometerY
Parameters related to the body-frame Y axis of the magnetometer
SdfMagnetometerZ
Parameters related to the body-frame Z axis of the magnetometer
SdfMaterial
The material of the visual element.
SdfMaterialPbr
Physically Based Rendering (PBR) material. There are two PBR workflows: metal and specular. While both workflows and their parameters can be specified at the same time, typically only one of them will be used (depending on the underlying renderer capability). It is also recommended to use the same workflow for all materials in the world.
SdfMaterialPbrMetal
PBR using the Metallic/Roughness workflow.
SdfMaterialPbrSpecular
PBR using the Specular/Glossiness workflow.
SdfMaterialScript
Name of material from an installed script file. This will override the color element if the script exists.
SdfMaterialShader
vertex, pixel, normal_map_object_space, normal_map_tangent_space
SdfMeshShape
Mesh shape
SdfMeshShapeSubmesh
Use a named submesh. The submesh must exist in the mesh specified by the uri
SdfModel
The frame inside this model whose pose will be set by the pose element of the model. i.e, the pose element specifies the pose of this frame instead of the model frame.
SdfModelInclude
Merge the included nested model into the top model
SdfModelState
Name of the model
SdfModelStateJoint
Name of the joint
SdfNavsat
These elements are specific to the NAVSAT sensor.
SdfNavsatPositionSensing
Parameters related to NAVSAT position measurement.
SdfNavsatPositionSensingHorizontal
Noise parameters for horizontal position measurement, in units of meters.
SdfNavsatPositionSensingVertical
Noise parameters for vertical position measurement, in units of meters.
SdfNavsatVelocitySensing
Parameters related to NAVSAT position measurement.
SdfNavsatVelocitySensingHorizontal
Noise parameters for horizontal velocity measurement, in units of meters/second.
SdfNavsatVelocitySensingVertical
Noise parameters for vertical velocity measurement, in units of meters/second.
SdfNoise
The type of noise. Currently supported types are: “none” (no noise). “gaussian” (draw noise values independently for each measurement from a Gaussian distribution). “gaussian_quantized” (“gaussian” plus quantization of outputs (ie. rounding))
SdfParams
SdfParticleEmitter
The type of a particle emitter. One of “box”, “cylinder”, “ellipsoid”, or “point”.
SdfPhysics
The type of the dynamics engine. Current options are ode, bullet, simbody and dart. Defaults to ode if left unspecified.
SdfPhysicsBullet
Bullet specific physics properties
SdfPhysicsBulletConstraints
Bullet constraint parameters.
SdfPhysicsBulletSolver
SdfPhysicsDart
DART specific physics properties
SdfPhysicsDartSolver
SdfPhysicsOde
ODE specific physics properties
SdfPhysicsOdeConstraints
ODE constraint parameters.
SdfPhysicsOdeSolver
SdfPhysicsSimbody
Simbody specific physics properties
SdfPhysicsSimbodyContact
Relationship among dissipation, coef. restitution, etc. d = dissipation coefficient (1/velocity) vc = capture velocity (velocity where e=e_max) vp = plastic velocity (smallest v where e=e_min) > vc Assume real COR=1 when v=0. e_min = given minimum COR, at v >= vp (a.k.a. plastic_coef_restitution) d = slope = (1-e_min)/vp OR, e_min = 1 - dvp e_max = maximum COR = 1-dvc, reached at v=vc e = 0, v <= vc = 1 - d*v, vc < v < vp = e_min, v >= vp
SdfPlaneShape
Plane shape
SdfPlugin
SdfPolylineShape
Defines an extruded polyline shape
SdfPopulation
A unique name for the population. This name must not match another population in the world.
SdfPopulationDistribution
Specifies the type of object distribution and its optional parameters.
SdfPose
Whether or not the euler angles are in degrees, otherwise they will be interpreted as radians by default.
SdfProjector
Name of the projector
SdfRay
These elements are specific to the ray (laser) sensor.
SdfRayNoise
The properties of the noise model that should be applied to generated scans
SdfRayRange
specifies range properties of each simulated ray
SdfRayScan
SdfRayScanHorizontal
SdfRayScanVertical
SdfRfid
SdfRfidtag
SdfRoad
Name of the road
SdfRoot
Version number of the SDFormat specification, consisting of major and minor versions delimited by a . character. A major version bump is required if older versions cannot be automatically converted to this version. A minor version bump is required when there are breaking changes that can be handled by the automatic conversion functionality encoded in the *.convert files.
SdfScene
Specifies the look of the environment.
SdfSceneFog
Controls fog
SdfSceneSky
Properties for the sky
SdfSceneSkyClouds
Information about clouds in the sky.
SdfSensor
The type name of the sensor. By default, SDFormat supports types air_pressure, altimeter, camera, contact, boundingbox_camera, boundingbox, custom, depth_camera, depth, force_torque, gps, gpu_lidar, gpu_ray, imu, lidar, logical_camera, magnetometer, multicamera, navsat, ray, rfid, rfidtag, rgbd_camera, rgbd, segmentation_camera, segmentation, sonar, thermal_camera, thermal, wireless_receiver, and wireless_transmitter. The “ray”, “gpu_ray”, and “gps” types are equivalent to “lidar”, “gpu_lidar”, and “navsat”, respectively. It is preferred to use “lidar”, “gpu_lidar”, and “navsat” since “ray”, “gpu_ray”, and “gps” will be deprecated. The “ray”, “gpu_ray”, and “gps” types are maintained for legacy support.
SdfSonar
These elements are specific to the sonar sensor.
SdfSphereShape
Sphere shape
SdfSphericalCoordinates
SdfState
Name of the world this state applies to
SdfStateDeletions
A list of names of deleted entities/
SdfStateInsertions
A list containing the entire description of entities inserted.
SdfSurface
The surface parameters
SdfSurfaceBounce
SdfSurfaceContact
SdfSurfaceContactBullet
Bullet contact parameters
SdfSurfaceContactOde
ODE contact parameters
SdfSurfaceFriction
SdfSurfaceFrictionBullet
SdfSurfaceFrictionOde
ODE friction parameters
SdfSurfaceFrictionTorsional
Parameters for torsional friction
SdfSurfaceFrictionTorsionalOde
Torsional friction parameters for ODE
SdfSurfaceSoftContact
SdfSurfaceSoftContactDart
soft contact pamameters based on paper: http://www.cc.gatech.edu/graphics/projects/Sumit/homepage/papers/sigasia11/jain_softcontacts_siga11.pdf
SdfTransceiver
These elements are specific to a wireless transceiver.
SdfVisual
Unique name for the visual element within the scope of the parent link.
SdfVisualMeta
Optional meta information for the visual. The information contained within this element should be used to provide additional feedback to an end user.
SdfWorld
Unique name of the world
SdfWorldAudio
Global audio properties.
SdfWorldInclude
Include resources from a URI. Included resources can only contain one ‘model’, ‘light’ or ‘actor’ element. The URI can point to a directory or a file. If the URI is a directory, it must conform to the model database structure (see /tutorials?tut=composition&cat=specification&#defining-models-in-separate-files).
SdfWorldWind
The wind tag specifies the type and properties of the wind.
Vector3d
Vector3i
XmlElement

Enums§

ElementData
SdfGeometry
The shape of the visual or collision object.

Functions§

from_str