From b79abc40f625157b5a9495ccf9016553182f46e7 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 28 Feb 2024 12:47:50 -0800 Subject: [PATCH] Copy 1.11 spec to 1.12 for libsdformat15 (#1375) * Set default spec version to 1.12 * Update Migration.md Signed-off-by: Steve Peters --- CMakeLists.txt | 2 +- Migration.md | 10 ++ sdf/1.12/1_11.convert | 2 + sdf/1.12/CMakeLists.txt | 89 +++++++++++ sdf/1.12/actor.sdf | 86 ++++++++++ sdf/1.12/air_pressure.sdf | 15 ++ sdf/1.12/air_speed.sdf | 11 ++ sdf/1.12/altimeter.sdf | 18 +++ sdf/1.12/atmosphere.sdf | 21 +++ sdf/1.12/audio_sink.sdf | 4 + sdf/1.12/audio_source.sdf | 30 ++++ sdf/1.12/battery.sdf | 12 ++ sdf/1.12/box_shape.sdf | 6 + sdf/1.12/camera.sdf | 230 +++++++++++++++++++++++++++ sdf/1.12/capsule_shape.sdf | 9 ++ sdf/1.12/collision.sdf | 34 ++++ sdf/1.12/contact.sdf | 12 ++ sdf/1.12/cylinder_shape.sdf | 9 ++ sdf/1.12/ellipsoid_shape.sdf | 6 + sdf/1.12/forcetorque.sdf | 54 +++++++ sdf/1.12/frame.sdf | 35 ++++ sdf/1.12/geometry.sdf | 20 +++ sdf/1.12/gps.sdf | 40 +++++ sdf/1.12/gripper.sdf | 30 ++++ sdf/1.12/gui.sdf | 60 +++++++ sdf/1.12/heightmap_shape.sdf | 44 ++++++ sdf/1.12/image_shape.sdf | 18 +++ sdf/1.12/imu.sdf | 120 ++++++++++++++ sdf/1.12/inertial.sdf | 233 +++++++++++++++++++++++++++ sdf/1.12/joint.sdf | 246 +++++++++++++++++++++++++++++ sdf/1.12/lidar.sdf | 78 +++++++++ sdf/1.12/light.sdf | 71 +++++++++ sdf/1.12/light_state.sdf | 10 ++ sdf/1.12/link.sdf | 51 ++++++ sdf/1.12/link_state.sdf | 40 +++++ sdf/1.12/logical_camera.sdf | 19 +++ sdf/1.12/magnetometer.sdf | 21 +++ sdf/1.12/material.sdf | 166 +++++++++++++++++++ sdf/1.12/mesh_shape.sdf | 20 +++ sdf/1.12/mimic.sdf | 37 +++++ sdf/1.12/model.sdf | 92 +++++++++++ sdf/1.12/model_state.sdf | 41 +++++ sdf/1.12/navsat.sdf | 40 +++++ sdf/1.12/noise.sdf | 43 +++++ sdf/1.12/particle_emitter.sdf | 120 ++++++++++++++ sdf/1.12/physics.sdf | 238 ++++++++++++++++++++++++++++ sdf/1.12/plane_shape.sdf | 9 ++ sdf/1.12/plugin.sdf | 13 ++ sdf/1.12/polyline_shape.sdf | 14 ++ sdf/1.12/population.sdf | 58 +++++++ sdf/1.12/pose.sdf | 43 +++++ sdf/1.12/projector.sdf | 32 ++++ sdf/1.12/ray.sdf | 78 +++++++++ sdf/1.12/rfid.sdf | 2 + sdf/1.12/rfidtag.sdf | 2 + sdf/1.12/road.sdf | 16 ++ sdf/1.12/root.sdf | 21 +++ sdf/1.12/scene.sdf | 86 ++++++++++ sdf/1.12/schema/types.xsd | 46 ++++++ sdf/1.12/sensor.sdf | 82 ++++++++++ sdf/1.12/sonar.sdf | 16 ++ sdf/1.12/sphere_shape.sdf | 6 + sdf/1.12/spherical_coordinates.sdf | 65 ++++++++ sdf/1.12/state.sdf | 41 +++++ sdf/1.12/surface.sdf | 245 ++++++++++++++++++++++++++++ sdf/1.12/transceiver.sdf | 34 ++++ sdf/1.12/visual.sdf | 38 +++++ sdf/1.12/world.sdf | 75 +++++++++ sdf/CMakeLists.txt | 1 + sdf/embedSdf.py | 3 +- src/Root_TEST.cc | 2 +- 71 files changed, 3618 insertions(+), 3 deletions(-) create mode 100644 sdf/1.12/1_11.convert create mode 100644 sdf/1.12/CMakeLists.txt create mode 100644 sdf/1.12/actor.sdf create mode 100644 sdf/1.12/air_pressure.sdf create mode 100644 sdf/1.12/air_speed.sdf create mode 100644 sdf/1.12/altimeter.sdf create mode 100644 sdf/1.12/atmosphere.sdf create mode 100644 sdf/1.12/audio_sink.sdf create mode 100644 sdf/1.12/audio_source.sdf create mode 100644 sdf/1.12/battery.sdf create mode 100644 sdf/1.12/box_shape.sdf create mode 100644 sdf/1.12/camera.sdf create mode 100644 sdf/1.12/capsule_shape.sdf create mode 100644 sdf/1.12/collision.sdf create mode 100644 sdf/1.12/contact.sdf create mode 100644 sdf/1.12/cylinder_shape.sdf create mode 100644 sdf/1.12/ellipsoid_shape.sdf create mode 100644 sdf/1.12/forcetorque.sdf create mode 100644 sdf/1.12/frame.sdf create mode 100644 sdf/1.12/geometry.sdf create mode 100644 sdf/1.12/gps.sdf create mode 100644 sdf/1.12/gripper.sdf create mode 100644 sdf/1.12/gui.sdf create mode 100644 sdf/1.12/heightmap_shape.sdf create mode 100644 sdf/1.12/image_shape.sdf create mode 100644 sdf/1.12/imu.sdf create mode 100644 sdf/1.12/inertial.sdf create mode 100644 sdf/1.12/joint.sdf create mode 100644 sdf/1.12/lidar.sdf create mode 100644 sdf/1.12/light.sdf create mode 100644 sdf/1.12/light_state.sdf create mode 100644 sdf/1.12/link.sdf create mode 100644 sdf/1.12/link_state.sdf create mode 100644 sdf/1.12/logical_camera.sdf create mode 100644 sdf/1.12/magnetometer.sdf create mode 100644 sdf/1.12/material.sdf create mode 100644 sdf/1.12/mesh_shape.sdf create mode 100644 sdf/1.12/mimic.sdf create mode 100644 sdf/1.12/model.sdf create mode 100644 sdf/1.12/model_state.sdf create mode 100644 sdf/1.12/navsat.sdf create mode 100644 sdf/1.12/noise.sdf create mode 100755 sdf/1.12/particle_emitter.sdf create mode 100644 sdf/1.12/physics.sdf create mode 100644 sdf/1.12/plane_shape.sdf create mode 100644 sdf/1.12/plugin.sdf create mode 100644 sdf/1.12/polyline_shape.sdf create mode 100644 sdf/1.12/population.sdf create mode 100644 sdf/1.12/pose.sdf create mode 100644 sdf/1.12/projector.sdf create mode 100644 sdf/1.12/ray.sdf create mode 100644 sdf/1.12/rfid.sdf create mode 100644 sdf/1.12/rfidtag.sdf create mode 100644 sdf/1.12/road.sdf create mode 100644 sdf/1.12/root.sdf create mode 100644 sdf/1.12/scene.sdf create mode 100644 sdf/1.12/schema/types.xsd create mode 100644 sdf/1.12/sensor.sdf create mode 100644 sdf/1.12/sonar.sdf create mode 100644 sdf/1.12/sphere_shape.sdf create mode 100644 sdf/1.12/spherical_coordinates.sdf create mode 100644 sdf/1.12/state.sdf create mode 100644 sdf/1.12/surface.sdf create mode 100644 sdf/1.12/transceiver.sdf create mode 100644 sdf/1.12/visual.sdf create mode 100644 sdf/1.12/world.sdf diff --git a/CMakeLists.txt b/CMakeLists.txt index be6e4394e..d58d35811 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,7 +9,7 @@ project (sdformat15 VERSION 15.0.0) # The protocol version has nothing to do with the package version. # It represents the current version of SDFormat implemented by the software -set (SDF_PROTOCOL_VERSION 1.11) +set (SDF_PROTOCOL_VERSION 1.12) OPTION(SDFORMAT_DISABLE_CONSOLE_LOGFILE "Disable the sdformat console logfile" OFF) diff --git a/Migration.md b/Migration.md index be560d702..edc36b79d 100644 --- a/Migration.md +++ b/Migration.md @@ -12,6 +12,14 @@ forward programmatically. This document aims to contain similar information to those files but with improved human-readability.. +## libsdformat 14.x to 15.x + +### Additions + +1. **New SDFormat specification version 1.12** + + Details about the 1.11 to 1.12 transition are explained below in this same + document + ## libsdformat 13.x to 14.x ### Additions @@ -576,6 +584,8 @@ ABI was broken for `sdf::Element`, and restored on version 11.2.1. + Changed to `_fixed_joint_lump__` to avoid confusion with scoped names + [BitBucket pull request 245](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/245) +## SDFormat specification 1.11 to 1.12 + ## SDFormat specification 1.10 to 1.11 ### Additions diff --git a/sdf/1.12/1_11.convert b/sdf/1.12/1_11.convert new file mode 100644 index 000000000..380267d62 --- /dev/null +++ b/sdf/1.12/1_11.convert @@ -0,0 +1,2 @@ + + diff --git a/sdf/1.12/CMakeLists.txt b/sdf/1.12/CMakeLists.txt new file mode 100644 index 000000000..85eb3fbc2 --- /dev/null +++ b/sdf/1.12/CMakeLists.txt @@ -0,0 +1,89 @@ +set (sdfs + actor.sdf + air_pressure.sdf + air_speed.sdf + altimeter.sdf + atmosphere.sdf + audio_source.sdf + audio_sink.sdf + battery.sdf + box_shape.sdf + camera.sdf + capsule_shape.sdf + collision.sdf + contact.sdf + cylinder_shape.sdf + ellipsoid_shape.sdf + frame.sdf + forcetorque.sdf + geometry.sdf + gps.sdf + gripper.sdf + gui.sdf + heightmap_shape.sdf + image_shape.sdf + imu.sdf + inertial.sdf + joint.sdf + lidar.sdf + light.sdf + light_state.sdf + link.sdf + link_state.sdf + logical_camera.sdf + magnetometer.sdf + material.sdf + mesh_shape.sdf + mimic.sdf + model.sdf + model_state.sdf + navsat.sdf + noise.sdf + particle_emitter.sdf + physics.sdf + plane_shape.sdf + plugin.sdf + polyline_shape.sdf + population.sdf + pose.sdf + projector.sdf + ray.sdf + rfidtag.sdf + rfid.sdf + road.sdf + root.sdf + scene.sdf + sensor.sdf + spherical_coordinates.sdf + sphere_shape.sdf + sonar.sdf + state.sdf + surface.sdf + transceiver.sdf + visual.sdf + world.sdf +) + +set (SDF_SCHEMA) + +foreach(FIL ${sdfs}) + get_filename_component(ABS_FIL ${FIL} ABSOLUTE) + get_filename_component(FIL_WE ${FIL} NAME_WE) + + list(APPEND SDF_SCHEMA "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd") + + add_custom_command( + OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd" + COMMAND ${Python3_EXECUTABLE} ${CMAKE_SOURCE_DIR}/tools/xmlschema.py + ARGS --sdf-dir ${CMAKE_CURRENT_SOURCE_DIR} --input-file ${ABS_FIL} --output-dir ${CMAKE_CURRENT_BINARY_DIR} + DEPENDS ${ABS_FIL} + COMMENT "Running xml schema compiler on ${FIL}" + VERBATIM) +endforeach() + +add_custom_target(schema1_12 ALL DEPENDS ${SDF_SCHEMA}) + +set_source_files_properties(${SDF_SCHEMA} PROPERTIES GENERATED TRUE) + +install(FILES 1_11.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.12) +install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.12) diff --git a/sdf/1.12/actor.sdf b/sdf/1.12/actor.sdf new file mode 100644 index 000000000..4ff1c4cc6 --- /dev/null +++ b/sdf/1.12/actor.sdf @@ -0,0 +1,86 @@ + + + A special kind of model which can have a scripted motion. This includes both global waypoint type animations and skeleton animations. + + + A unique name for the actor. + + + + + + Skin file which defines a visual and the underlying skeleton which moves it. + + + Path to skin file, accepted formats: COLLADA, BVH. + + + + Scale the skin's size. + + + + + Animation file defines an animation for the skeleton in the skin. The skeleton must be compatible with the skin skeleton. + + + Unique name for animation. + + + + Path to animation file. Accepted formats: COLLADA, BVH. + + + Scale for the animation skeleton. + + + Set to true so the animation is interpolated on X. + + + + + Adds scripted trajectories to the actor. + + + Set this to true for the script to be repeated in a loop. For a fluid continuous motion, make sure the last waypoint matches the first one. + + + + This is the time to wait before starting the script. If running in a loop, this time will be waited before starting each cycle. + + + + Set to true if the animation should start as soon as the simulation starts playing. It is useful to set this to false if the animation should only start playing only when triggered by a plugin, for example. + + + + The trajectory contains a series of keyframes to be followed. + + Unique id for a trajectory. + + + + If it matches the type of an animation, they will be played at the same time. + + + + 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. + + + + Each point in the trajectory. + + The time in seconds, counted from the beginning of the script, when the pose should be reached. + + + The pose which should be reached at the given time. + + + + + + + + + + diff --git a/sdf/1.12/air_pressure.sdf b/sdf/1.12/air_pressure.sdf new file mode 100644 index 000000000..07fe5b564 --- /dev/null +++ b/sdf/1.12/air_pressure.sdf @@ -0,0 +1,15 @@ + + These elements are specific to an air pressure sensor. + + + The initial altitude in meters. This value can be used by a sensor implementation to augment the altitude of the sensor. For example, if you are using simulation instead of creating a 1000 m mountain model on which to place your sensor, you could instead set this value to 1000 and place your model on a ground plane with a Z height of zero. + + + + + Noise parameters for the pressure data. + + + + + diff --git a/sdf/1.12/air_speed.sdf b/sdf/1.12/air_speed.sdf new file mode 100644 index 000000000..1313f705a --- /dev/null +++ b/sdf/1.12/air_speed.sdf @@ -0,0 +1,11 @@ + + These elements are specific to an air speed sensor. This sensor determines speed based on the differential between static and dynamic pressure. + + + + Noise parameters for the pressure data. + + + + + diff --git a/sdf/1.12/altimeter.sdf b/sdf/1.12/altimeter.sdf new file mode 100644 index 000000000..66ddee579 --- /dev/null +++ b/sdf/1.12/altimeter.sdf @@ -0,0 +1,18 @@ + + These elements are specific to an altimeter sensor. + + + + Noise parameters for vertical position + + + + + + + Noise parameters for vertical velocity + + + + + diff --git a/sdf/1.12/atmosphere.sdf b/sdf/1.12/atmosphere.sdf new file mode 100644 index 000000000..641faccb9 --- /dev/null +++ b/sdf/1.12/atmosphere.sdf @@ -0,0 +1,21 @@ + + + The atmosphere tag specifies the type and properties of the atmosphere model. + + + The type of the atmosphere engine. Current options are adiabatic. Defaults to adiabatic if left unspecified. + + + + Temperature at sea level in kelvins. + + + + Pressure at sea level in pascals. + + + + Temperature gradient with respect to increasing altitude at sea level in units of K/m. + + + diff --git a/sdf/1.12/audio_sink.sdf b/sdf/1.12/audio_sink.sdf new file mode 100644 index 000000000..d3bd0711d --- /dev/null +++ b/sdf/1.12/audio_sink.sdf @@ -0,0 +1,4 @@ + + + An audio sink. + diff --git a/sdf/1.12/audio_source.sdf b/sdf/1.12/audio_source.sdf new file mode 100644 index 000000000..b6ee6069a --- /dev/null +++ b/sdf/1.12/audio_source.sdf @@ -0,0 +1,30 @@ + + + An audio source. + + + URI of the audio media. + + + + Pitch for the audio media, in Hz + + + + Gain for the audio media, in dB. + + + + List of collision objects that will trigger audio playback. + + Name of child collision element that will trigger audio playback. + + + + + True to make the audio source loop playback. + + + + + diff --git a/sdf/1.12/battery.sdf b/sdf/1.12/battery.sdf new file mode 100644 index 000000000..dc6f8deb6 --- /dev/null +++ b/sdf/1.12/battery.sdf @@ -0,0 +1,12 @@ + + + Description of a battery. + + + Unique name for the battery. + + + + Initial voltage in volts. + + diff --git a/sdf/1.12/box_shape.sdf b/sdf/1.12/box_shape.sdf new file mode 100644 index 000000000..826ab37a2 --- /dev/null +++ b/sdf/1.12/box_shape.sdf @@ -0,0 +1,6 @@ + + Box shape + + The three side lengths of the box. The origin of the box is in its geometric center (inside the center of the box). + + diff --git a/sdf/1.12/camera.sdf b/sdf/1.12/camera.sdf new file mode 100644 index 000000000..8fd218caf --- /dev/null +++ b/sdf/1.12/camera.sdf @@ -0,0 +1,230 @@ + + These elements are specific to camera sensors. + + + An optional name for the camera. + + + + If the camera will be triggered by a topic + + + + Name of the camera info + + + + Name of the topic that will trigger the camera if enabled + + + + Horizontal field of view + + + + The image size in pixels and format. + + Width in pixels + + + Height in pixels + + + (L8|L16|R_FLOAT16|R_FLOAT32|R8G8B8|B8G8R8|BAYER_RGGB8|BAYER_BGGR8|BAYER_GBRG8|BAYER_GRBG8) + + + Value used for anti-aliasing + + + + + The near and far clip planes. Objects closer or farther than these planes are not rendered. + + + Near clipping plane + + + + Far clipping plane + + + + + Enable or disable saving of camera frames. + + True = saving enabled + + + The path name which will hold the frame data. If path name is relative, then directory is relative to current working directory. + + + + + Depth camera parameters + + Type of output + + + The near and far clip planes. Objects closer or farther than these planes are not detected by the depth camera. + + + Near clipping plane for depth camera + + + + Far clipping plane for depth camera + + + + + + + The segmentation type of the segmentation camera. Valid options are: + - semantic: Semantic segmentation, which provides 2 images: + 1. A grayscale image, with the pixel values representing the label of an object + 2. A colored image, with the pixel values being a unique color for each label + + - panoptic | instance: Panoptic segmentation, which provides an image where each pixel + has 1 channel for label value of the object and 2 channels for the + number of the instances of that label, and a colored image which its + pixels have a unique color for each instance. + + + + + + The boundingbox type of the boundingbox camera. Valid options are: + - 2d | visible_2d | visible_box_2d: a visible 2d box mode which provides axis aligned 2d boxes + on the visible parts of the objects + + - full_2d | full_box_2d: a full 2d box mode which provides axis aligned 2d boxes that fills the + object dimentions, even if it has an occluded part + + - 3d: a 3d mode which provides oriented 3d boxes + + + + + The properties of the noise model that should be applied to generated images + + The type of noise. Currently supported types are: "gaussian" (draw additive noise values independently for each pixel from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + + + Lens distortion to be applied to camera images. See http://en.wikipedia.org/wiki/Distortion_(optics)#Software_correction + + The radial distortion coefficient k1 + + + The radial distortion coefficient k2 + + + The radial distortion coefficient k3 + + + The tangential distortion coefficient p1 + + + The tangential distortion coefficient p2 + + + The distortion center or principal point + + + + + Lens projection description + + + Type of the lens mapping. Supported values are gnomonical, stereographic, equidistant, equisolid_angle, orthographic, custom. For gnomonical (perspective) projection, it is recommended to specify a horizontal_fov of less than or equal to 90° + + + If true the image will be scaled to fit horizontal FOV, otherwise it will be shown according to projection type parameters + + + + Definition of custom mapping function in a form of r=c1*f*fun(theta/c2 + c3). See https://en.wikipedia.org/wiki/Fisheye_lens#Mapping_function + + Linear scaling constant + + + Angle scaling constant + + + Angle offset constant + + + Focal length of the optical system. Note: It's not a focal length of the lens in a common sense! This value is ignored if 'scale_to_fov' is set to true + + + Possible values are 'sin', 'tan' and 'id' + + + + + Everything outside of the specified angle will be hidden, 90° by default + + + + Resolution of the environment cube map used to draw the world + + + + 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) + + X focal length (in pixels, overrides horizontal_fov) + + + Y focal length (in pixels, overrides horizontal_fov) + + + X principal point (in pixels) + + + Y principal point (in pixels) + + + XY axis skew + + + + + 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. + + X focal length for projection matrix(in pixels, overrides fx) + + + Y focal length for projection matrix(in pixels, overrides fy) + + + X principal point for projection matrix(in pixels, overrides cx) + + + Y principal point for projection matrix(in pixels, overrides cy) + + + X translation for projection matrix (in pixels) + + + Y translation for projection matrix (in pixels) + + + + + + + + + + An optional frame id name to be used in the camera_info message header. + + + + diff --git a/sdf/1.12/capsule_shape.sdf b/sdf/1.12/capsule_shape.sdf new file mode 100644 index 000000000..2831099ba --- /dev/null +++ b/sdf/1.12/capsule_shape.sdf @@ -0,0 +1,9 @@ + + Capsule shape + + Radius of the capsule + + + Length of the cylindrical portion of the capsule along the z axis + + diff --git a/sdf/1.12/collision.sdf b/sdf/1.12/collision.sdf new file mode 100644 index 000000000..425300cff --- /dev/null +++ b/sdf/1.12/collision.sdf @@ -0,0 +1,34 @@ + + + The collision properties of a link. Note that this can be different from the visual properties of a link, for example, simpler collision models are often used to reduce computation time. + + + Unique name for the collision element within the scope of the parent link. + + + + intensity value returned by laser sensor. + + + + Maximum number of contacts allowed between two entities. This value overrides the max_contacts element defined in physics. + + + + + Mass Density of the collision geometry. + This is used to determine mass and inertia values during automatic calculation. + Default is the density of water 1000 kg/m^3. + + + + + Parent tag to hold user-defined custom params for mesh inertia calculator + + + + + + + + diff --git a/sdf/1.12/contact.sdf b/sdf/1.12/contact.sdf new file mode 100644 index 000000000..d1cde50ac --- /dev/null +++ b/sdf/1.12/contact.sdf @@ -0,0 +1,12 @@ + + These elements are specific to the contact sensor. + + + name of the collision element within a link that acts as the contact sensor. + + + + Topic on which contact data is published. + + + diff --git a/sdf/1.12/cylinder_shape.sdf b/sdf/1.12/cylinder_shape.sdf new file mode 100644 index 000000000..771596ba4 --- /dev/null +++ b/sdf/1.12/cylinder_shape.sdf @@ -0,0 +1,9 @@ + + Cylinder shape + + Radius of the cylinder + + + Length of the cylinder along the z axis + + diff --git a/sdf/1.12/ellipsoid_shape.sdf b/sdf/1.12/ellipsoid_shape.sdf new file mode 100644 index 000000000..821aadf12 --- /dev/null +++ b/sdf/1.12/ellipsoid_shape.sdf @@ -0,0 +1,6 @@ + + Ellipsoid shape + + The three radii of the ellipsoid. The origin of the ellipsoid is in its geometric center (inside the center of the ellipsoid). + + diff --git a/sdf/1.12/forcetorque.sdf b/sdf/1.12/forcetorque.sdf new file mode 100644 index 000000000..5a1846951 --- /dev/null +++ b/sdf/1.12/forcetorque.sdf @@ -0,0 +1,54 @@ + + These elements are specific to the force torque sensor. + + + Frame in which to report the wrench values. Currently supported frames are: + "parent" report the wrench expressed in the orientation of the parent link frame, + "child" report the wrench expressed in the orientation of the child link frame, + "sensor" report the wrench expressed in the orientation of the joint sensor frame. + Note that for each option the point with respect to which the + torque component of the wrench is expressed is the joint origin. + + + + + Direction of the wrench measured by the sensor. The supported options are: + "parent_to_child" if the measured wrench is the one applied by the parent link on the child link, + "child_to_parent" if the measured wrench is the one applied by the child link on the parent link. + + + + + These elements are specific to measurement-frame force, + which is expressed in Newtons + + Force along the X axis + + + + Force along the Y axis + + + + Force along the Z axis + + + + + + These elements are specific to measurement-frame torque, + which is expressed in Newton-meters + + Torque about the X axis + + + + Force about the Y axis + + + + Torque about the Z axis + + + + diff --git a/sdf/1.12/frame.sdf b/sdf/1.12/frame.sdf new file mode 100644 index 000000000..74802fd7e --- /dev/null +++ b/sdf/1.12/frame.sdf @@ -0,0 +1,35 @@ + + + A frame of reference in which poses may be expressed. + + + + Name of the frame. It must be unique whithin its scope (model/world), + i.e., it must not match the name of another frame, link, joint, or model + within the same scope. + + + + + + If specified, this frame is attached to the specified frame. The specified + frame must be within the same scope and may be defined implicitly, i.e., + the name of any //frame, //model, //joint, or //link within the same scope + may be used. + + If missing, this frame is attached to the containing scope's frame. Within + a //world scope this is the implicit world frame, and within a //model + scope this is the implicit model frame. + + A frame moves jointly with the frame it is @attached_to. This is different + from //pose/@relative_to. @attached_to defines how the frame is attached + to a //link, //model, or //world frame, while //pose/@relative_to defines + how the frame's pose is represented numerically. As a result, following + the chain of @attached_to attributes must always lead to a //link, + //model, //world, or //joint (implicitly attached_to its child //link). + + + + + + diff --git a/sdf/1.12/geometry.sdf b/sdf/1.12/geometry.sdf new file mode 100644 index 000000000..884902afb --- /dev/null +++ b/sdf/1.12/geometry.sdf @@ -0,0 +1,20 @@ + + + The shape of the visual or collision object. + + + You can use the empty tag to make empty geometries. + + + + + + + + + + + + + + diff --git a/sdf/1.12/gps.sdf b/sdf/1.12/gps.sdf new file mode 100644 index 000000000..95e004925 --- /dev/null +++ b/sdf/1.12/gps.sdf @@ -0,0 +1,40 @@ + + These elements are specific to the GPS sensor. + + + + Parameters related to GPS position measurement. + + + + Noise parameters for horizontal position measurement, in units of meters. + + + + + + Noise parameters for vertical position measurement, in units of meters. + + + + + + + + Parameters related to GPS position measurement. + + + + Noise parameters for horizontal velocity measurement, in units of meters/second. + + + + + + Noise parameters for vertical velocity measurement, in units of meters/second. + + + + + + diff --git a/sdf/1.12/gripper.sdf b/sdf/1.12/gripper.sdf new file mode 100644 index 000000000..12fd0b341 --- /dev/null +++ b/sdf/1.12/gripper.sdf @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdf/1.12/gui.sdf b/sdf/1.12/gui.sdf new file mode 100644 index 000000000..3a87763a7 --- /dev/null +++ b/sdf/1.12/gui.sdf @@ -0,0 +1,60 @@ + + + + + + + + + + + + + + + + + + + + + Set the type of projection for the camera. Valid values are "perspective" and "orthographic". + + + + + + + Name of the tracked visual. If no name is provided, the remaining settings will be applied whenever tracking is triggered in the GUI. + + + + Minimum distance between the camera and the tracked visual. This parameter is only used if static is set to false. + + + + Maximum distance between the camera and the tracked visual. This parameter is only used if static is set to false. + + + + If set to true, the position of the camera is fixed relatively to the model or to the world, depending on the value of the use_model_frame element. Otherwise, the position of the camera may vary but the distance between the camera and the model will depend on the value of the min_dist and max_dist elements. In any case, the camera will always follow the model by changing its orientation. + + + + If set to true, the position of the camera is relative to the model reference frame, which means that its position relative to the model will not change. Otherwise, the position of the camera is relative to the world reference frame, which means that its position relative to the world will not change. This parameter is only used if static is set to true. + + + + The position of the camera's reference frame. This parameter is only used if static is set to true. If use_model_frame is set to true, the position is relative to the model reference frame, otherwise it represents world coordinates. + + + + If set to true, the camera will inherit the yaw rotation of the tracked model. This parameter is only used if static and use_model_frame are set to true. + + + + + + + + diff --git a/sdf/1.12/heightmap_shape.sdf b/sdf/1.12/heightmap_shape.sdf new file mode 100644 index 000000000..7a7462298 --- /dev/null +++ b/sdf/1.12/heightmap_shape.sdf @@ -0,0 +1,44 @@ + + A heightmap based on a 2d grayscale image. + + URI to a grayscale image file + + + The size of the heightmap in world units. + When loading an image: "size" is used if present, otherwise defaults to 1x1x1. + When loading a DEM: "size" is used if present, otherwise defaults to true size of DEM. + + + + A position offset. + + + + 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. + + Size of the applied texture in meters. + + + Diffuse texture image filename + + + Normalmap texture image filename + + + + The blend tag controls how two adjacent textures are mixed. The number of blend elements should equal one less than the number of textures. + + Min height of a blend layer + + + Distance over which the blend occurs + + + + Set if the rendering engine will use terrain paging + + + Samples per heightmap datum. For rasterized heightmaps, this indicates the number of samples to take per pixel. Using a higher value, e.g. 2, will generally improve the quality of the heightmap but lower performance. + + + diff --git a/sdf/1.12/image_shape.sdf b/sdf/1.12/image_shape.sdf new file mode 100644 index 000000000..369de7c5e --- /dev/null +++ b/sdf/1.12/image_shape.sdf @@ -0,0 +1,18 @@ + + Extrude a set of boxes from a grayscale image. + + URI of the grayscale image file + + + Scaling factor applied to the image + + + Grayscale threshold + + + Height of the extruded boxes + + + The amount of error in the model + + diff --git a/sdf/1.12/imu.sdf b/sdf/1.12/imu.sdf new file mode 100644 index 000000000..25690c8f1 --- /dev/null +++ b/sdf/1.12/imu.sdf @@ -0,0 +1,120 @@ + + These elements are specific to the IMU sensor. + + + + + + This string represents special hardcoded use cases that are commonly seen with typical robot IMU's: + - CUSTOM: use Euler angle custom_rpy orientation specification. + The orientation of the IMU's reference frame is defined by adding the custom_rpy rotation + to the parent_frame. + - NED: The IMU XYZ aligns with NED, where NED orientation relative to Gazebo world + is defined by the SphericalCoordinates class. + - ENU: The IMU XYZ aligns with ENU, where ENU orientation relative to Gazebo world + is defined by the SphericalCoordinates class. + - NWU: The IMU XYZ aligns with NWU, where NWU orientation relative to Gazebo world + is defined by the SphericalCoordinates class. + - GRAV_UP: where direction of gravity maps to IMU reference frame Z-axis with Z-axis pointing in + the opposite direction of gravity. IMU reference frame X-axis direction is defined by grav_dir_x. + Note if grav_dir_x is parallel to gravity direction, this configuration fails. + Otherwise, IMU reference frame X-axis is defined by projection of grav_dir_x onto a plane + normal to the gravity vector. IMU reference frame Y-axis is a vector orthogonal to both + X and Z axis following the right hand rule. + - GRAV_DOWN: where direction of gravity maps to IMU reference frame Z-axis with Z-axis pointing in + the direction of gravity. IMU reference frame X-axis direction is defined by grav_dir_x. + Note if grav_dir_x is parallel to gravity direction, this configuration fails. + Otherwise, IMU reference frame X-axis is defined by projection of grav_dir_x onto a plane + normal to the gravity vector. IMU reference frame Y-axis is a vector orthogonal to both + X and Z axis following the right hand rule. + + + + + This field and parent_frame are used when localization is set to CUSTOM. + Orientation (fixed axis roll, pitch yaw) transform from parent_frame to this IMU's reference frame. + Some common examples are: + - IMU reports in its local frame on boot. IMU sensor frame is the reference frame. + Example: parent_frame="", custom_rpy="0 0 0" + - IMU reports in Gazebo world frame. + Example sdf: parent_frame="world", custom_rpy="0 0 0" + - IMU reports in NWU frame. + Uses SphericalCoordinates class to determine world frame in relation to magnetic north and gravity; + i.e. rotation between North-West-Up and world (+X,+Y,+Z) frame is defined by SphericalCoordinates class. + Example sdf given world is NWU: parent_frame="world", custom_rpy="0 0 0" + - IMU reports in NED frame. + Uses SphericalCoordinates class to determine world frame in relation to magnetic north and gravity; + i.e. rotation between North-East-Down and world (+X,+Y,+Z) frame is defined by SphericalCoordinates class. + Example sdf given world is NWU: parent_frame="world", custom_rpy="M_PI 0 0" + - IMU reports in ENU frame. + Uses SphericalCoordinates class to determine world frame in relation to magnetic north and gravity; + i.e. rotation between East-North-Up and world (+X,+Y,+Z) frame is defined by SphericalCoordinates class. + Example sdf given world is NWU: parent_frame="world", custom_rpy="0 0 -0.5*M_PI" + - IMU reports in ROS optical frame as described in http://www.ros.org/reps/rep-0103.html#suffix-frames, which is + (z-forward, x-left to right when facing +z, y-top to bottom when facing +z). + (default gazebo camera is +x:view direction, +y:left, +z:up). + Example sdf: parent_frame="local", custom_rpy="-0.5*M_PI 0 -0.5*M_PI" + + + + Name of parent frame which the custom_rpy transform is defined relative to. + It can be any valid fully scoped Gazebo Link name or the special reserved "world" frame. + If left empty, use the sensor's own local frame. + + + + + + Used when localization is set to GRAV_UP or GRAV_DOWN, a projection of this vector + into a plane that is orthogonal to the gravity vector + defines the direction of the IMU reference frame's X-axis. + grav_dir_x is defined in the coordinate frame as defined by the parent_frame element. + + + + Name of parent frame in which the grav_dir_x vector is defined. + It can be any valid fully scoped Gazebo Link name or the special reserved "world" frame. + If left empty, use the sensor's own local frame. + + + + + + + These elements are specific to body-frame angular velocity, + which is expressed in radians per second + + Angular velocity about the X axis + + + + Angular velocity about the Y axis + + + + Angular velocity about the Z axis + + + + + + These elements are specific to body-frame linear acceleration, + which is expressed in meters per second squared + + Linear acceleration about the X axis + + + + Linear acceleration about the Y axis + + + + Linear acceleration about the Z axis + + + + + + Some IMU sensors rely on external filters to produce orientation estimates. True to generate and output orientation data, false to disable orientation data generation. + + diff --git a/sdf/1.12/inertial.sdf b/sdf/1.12/inertial.sdf new file mode 100644 index 000000000..99a3538eb --- /dev/null +++ b/sdf/1.12/inertial.sdf @@ -0,0 +1,233 @@ + + + + The link's mass, position of its center of mass, its central inertia + properties, and optionally its fluid added mass. + + + + + Set to true if you want automatic computation for the moments of inertia (ixx, iyy, izz) + and products of inertia(ixy, iyz, ixz). Default value is false. + + + + + The mass of the link. + + + + + Mass Density of the collision geometry. + This is used to determine mass and inertia values during automatic calculation. + This density value would be overwritten by the density value in collision. + Default is the density of water 1000 kg/m^3. + + + + + + Parent tag to hold user-defined custom params for mesh inertia calculator + The elements used under this would be overwritten by the elements in auto_inertia_params + in collision. + + + + + + This pose (translation, rotation) describes the position and orientation + of the link's center-of-mass-frame C relative to the link-frame L. + The first three components (x y z) specify the position vector from Lo + (the link-frame origin) to Co (the link's center of mass) as + `x L̂x + y L̂y + z L̂ᴢ`, where L̂x, L̂y, L̂ᴢ are link-frame L's orthogonal unit + vectors. The subsequent values characterize C's orientation relative to + link-frame L as a sequence of Euler rotations + (r p y) documented in http://sdformat.org/tutorials?tut=specify_pose, + or as a quaternion (x y z w), where w is the scalar component. + + + + 'euler_rpy' by default. Supported rotation formats are + 'euler_rpy', Euler angles representation in roll, pitch, yaw. The pose is expected to have 6 values. + 'quat_xyzw', Quaternion representation in x, y, z, w. The pose is expected to have 7 values. + + + + + + Whether or not the euler angles are in degrees, otherwise they will be interpreted as radians by default. + + + + + + + + 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 + + + + The link's moment of inertia about Co (the link's center of mass) for Ĉx. + + + + + The link's product of inertia about Co (the link's center of mass) for + Ĉx and Ĉy, where the product of inertia convention -m x y (not +m x y) + is used. If Ĉx or Ĉy is a principal inertia direction, ixy = 0. + + + + + The link's product of inertia about Co (the link's center of mass) for + Ĉx and Ĉz, where the product of inertia convention -m x z (not +m x z) + is used. If Ĉx or Ĉz is a principal inertia direction, ixz = 0. + + + + + The link's moment of inertia about Co (the link's center of mass) for Ĉy. + + + + + The link's product of inertia about Co (the link's center of mass) for + Ĉy and Ĉz, where the product of inertia convention -m y z (not +m y z) + is used. If Ĉy or Ĉz is a principal inertia direction, iyz = 0. + + + + + The link's moment of inertia about Co (the link's center of mass) for Ĉz. + + + + + + + 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). + + + + Added mass in the X axis due to linear acceleration in the X axis, in kg. + + + + + Added mass in the X axis due to linear acceleration in the Y axis, and vice-versa, in kg. + + + + + Added mass in the X axis due to linear acceleration in the Z axis, and vice-versa, in kg. + + + + + Added mass in the X axis due to angular acceleration about the X axis, and vice-versa, in kg * m. + + + + + Added mass in the X axis due to angular acceleration about the Y axis, and vice-versa, in kg * m. + + + + + Added mass in the X axis due to angular acceleration about the Z axis, and vice-versa, in kg * m. + + + + + Added mass in the Y axis due to linear acceleration in the Y axis, in kg. + + + + + Added mass in the Y axis due to linear acceleration in the Z axis, and vice-versa, in kg. + + + + + Added mass in the Y axis due to angular acceleration about the X axis, and vice-versa, in kg * m. + + + + + Added mass in the Y axis due to angular acceleration about the Y axis, and vice-versa, in kg * m. + + + + + Added mass in the Y axis due to angular acceleration about the Z axis, and vice-versa, in kg * m. + + + + + Added mass in the Z axis due to linear acceleration in the Z axis, in kg. + + + + + Added mass in the Z axis due to angular acceleration about the X axis, and vice-versa, in kg * m. + + + + + Added mass in the Z axis due to angular acceleration about the Y axis, and vice-versa, in kg * m. + + + + + Added mass in the Z axis due to angular acceleration about the Z axis, and vice-versa, in kg * m. + + + + + Added mass moment about the X axis due to angular acceleration about the X axis, in kg * m^2. + + + + + Added mass moment about the X axis due to angular acceleration about the Y axis, and vice-versa, in kg * m^2. + + + + + Added mass moment about the X axis due to angular acceleration about the Z axis, and vice-versa, in kg * m^2. + + + + + Added mass moment about the Y axis due to angular acceleration about the Y axis, in kg * m^2. + + + + + Added mass moment about the Y axis due to angular acceleration about the Z axis, and vice-versa, in kg * m^2. + + + + + Added mass moment about the Z axis due to angular acceleration about the Z axis, in kg * m^2. + + + + diff --git a/sdf/1.12/joint.sdf b/sdf/1.12/joint.sdf new file mode 100644 index 000000000..41ef0c372 --- /dev/null +++ b/sdf/1.12/joint.sdf @@ -0,0 +1,246 @@ + + + A joint connects two links with kinematic and dynamic properties. By default, the pose of a joint is expressed in the child link frame. + + + A unique name for the joint within its scope. + + + + 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. + + + + + Name of the parent frame or "world". + + + + Name of the child frame. The value "world" may not be specified. + + + + Parameter for gearbox joints. Given theta_1 and theta_2 defined in description for gearbox_reference_body, theta_2 = -gearbox_ratio * theta_1. + + + + Parameter for gearbox joints. Gearbox ratio is enforced over two joint angles. First joint angle (theta_1) is the angle from the gearbox_reference_body to the parent link in the direction of the axis element and the second joint angle (theta_2) is the angle from the gearbox_reference_body to the child link in the direction of the axis2 element. + + + + + Parameter for screw joints representing the ratio between rotation + and translation of the joint. This parameter has been interpreted by + gazebo-classic as having units of radians / meter with a positive value + corresponding to a left-handed thread. + The parameter is now deprecated in favor of `screw_thread_pitch`. + + + + + + A parameter for screw joint kinematics, representing the + axial distance traveled for each revolution of the joint, + with units of meters / revolution with a positive value corresponding + to a right-handed thread. + This parameter supersedes `thread_pitch`. + + + + + + Parameters related to the axis of rotation for revolute joints, + the axis of translation for prismatic joints. + + + + Represents the x,y,z components of the axis unit vector. The axis is + expressed in the joint frame unless a different frame is expressed in + the expressed_in attribute. The vector should be normalized. + + + + Name of frame in whose coordinates the xyz unit vector is expressed. + + + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. + + + The physical static friction value of the joint. + + + The spring reference position for this joint axis. + + + The spring stiffness for this joint axis. + + + + specifies the limits of this joint + + Specifies the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + Specifies the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + A value for enforcing the maximum joint effort applied. Limit is not enforced if value is negative. + + + A value for enforcing the maximum joint velocity. + + + + Joint stop stiffness. + + + + Joint stop dissipation. + + + + + + + + + + + Parameters related to the second axis of rotation for revolute2 joints and universal joints. + + + + Represents the x,y,z components of the axis unit vector. The axis is + expressed in the joint frame unless a different frame is expressed in + the expressed_in attribute. The vector should be normalized. + + + + Name of frame in whose coordinates the xyz unit vector is expressed. + + + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. EXPERIMENTAL: if damping coefficient is negative and implicit_spring_damper is true, adaptive damping is used. + + + The physical static friction value of the joint. + + + The spring reference position for this joint axis. + + + The spring stiffness for this joint axis. + + + + + + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + Joint stop stiffness. Supported physics engines: SimBody. + + + + Joint stop dissipation. Supported physics engines: SimBody. + + + + + + + + + + Parameters that are specific to a certain physics engine. + + Simbody specific parameters + + Force cut in the multibody graph at this joint. + + + + ODE specific parameters + + If cfm damping is set to true, ODE will use CFM to simulate damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. + + + + If implicit_spring_damper is set to true, ODE will use CFM, ERP to simulate stiffness and damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. This replaces cfm_damping parameter in SDFormat 1.4. + + + + Scale the excess for in a joint motor at joint limits. Should be between zero and one. + + + Constraint force mixing for constrained directions + + + Error reduction parameter for constrained directions + + + Bounciness of the limits + + + Maximum force or torque used to reach the desired velocity. + + + The desired velocity of the joint. Should only be set if you want the joint to move on load. + + + + + + Constraint force mixing parameter used by the joint stop + + + Error reduction parameter used by the joint stop + + + + + + + Suspension constraint force mixing parameter + + + Suspension error reduction parameter + + + + + + If provide feedback is set to true, physics engine will compute the constraint forces at this joint. + + + + + + diff --git a/sdf/1.12/lidar.sdf b/sdf/1.12/lidar.sdf new file mode 100644 index 000000000..f0100a9a3 --- /dev/null +++ b/sdf/1.12/lidar.sdf @@ -0,0 +1,78 @@ + + These elements are specific to the lidar sensor. + + + + + + + + The number of simulated lidar rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is not equal to one, range data is interpolated. + + + + + + + + Must be greater or equal to min_angle + + + + + + + + The number of simulated lidar rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is not equal to one, range data is interpolated. + + + + + + + + Must be greater or equal to min_angle + + + + + + + specifies range properties of each simulated lidar + + The minimum distance for each lidar ray. + + + The maximum distance for each lidar ray. + + + Linear resolution of each lidar ray. + + + + + The properties of the noise model that should be applied to generated scans + + The type of noise. Currently supported types are: "gaussian" (draw noise values independently for each beam from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + + + + + + diff --git a/sdf/1.12/light.sdf b/sdf/1.12/light.sdf new file mode 100644 index 000000000..356bad19a --- /dev/null +++ b/sdf/1.12/light.sdf @@ -0,0 +1,71 @@ + + + The light element describes a light source. + + + A unique name for the light. + + + + The light type: point, directional, spot. + + + + When true, the light will cast shadows. + + + + When true, the light is on. + + + + If true, the light is visualized in the GUI + + + + Scale factor to set the relative power of a light. + + + + + + Diffuse light color + + + Specular light color + + + + Light attenuation + + Range of the light + + + The linear attenuation factor: 1 means attenuate evenly over the distance. + + + The constant attenuation factor: 1.0 means never attenuate, 0.0 is complete attenutation. + + + The quadratic attenuation factor: adds a curvature to the attenuation. + + + + + Direction of the light, only applicable for spot and directional lights. + + + + Spot light parameters + + Angle covered by the bright inner cone + + + Angle covered by the outer cone + + + The rate of falloff between the inner and outer cones. 1.0 means a linear falloff, less means slower falloff, higher means faster falloff. + + + + diff --git a/sdf/1.12/light_state.sdf b/sdf/1.12/light_state.sdf new file mode 100644 index 000000000..673efcdb4 --- /dev/null +++ b/sdf/1.12/light_state.sdf @@ -0,0 +1,10 @@ + + + Light state + + + Name of the light + + + + diff --git a/sdf/1.12/link.sdf b/sdf/1.12/link.sdf new file mode 100644 index 000000000..b518ff3c5 --- /dev/null +++ b/sdf/1.12/link.sdf @@ -0,0 +1,51 @@ + + + A physical link with inertia, collision, and visual properties. A link must be a child of a model, and any number of links may exist in a model. + + + A unique name for the link within the scope of the model. + + + + If true, the link is affected by gravity. + + + + If true, the link is affected by the wind. + + + + If true, the link can collide with other links in the model. Two links within a model will collide if link1.self_collide OR link2.self_collide. Links connected by a joint will never collide. + + + + If true, the link is kinematic only + + + + If true, the link will have 6DOF and be a direct child of world. + + + + Exponential damping of the link's velocity. + + Linear damping + + + Angular damping + + + + + + + + + + + + + + + + diff --git a/sdf/1.12/link_state.sdf b/sdf/1.12/link_state.sdf new file mode 100644 index 000000000..28fff465d --- /dev/null +++ b/sdf/1.12/link_state.sdf @@ -0,0 +1,40 @@ + + + Link state + + + Name of the link + + + + Velocity of the link. The x, y, z components of the pose + correspond to the linear velocity of the link, and the roll, pitch, yaw + components correspond to the angular velocity of the link + + + + + Acceleration of the link. The x, y, z components of the pose + correspond to the linear acceleration of the link, and the roll, + pitch, yaw components correspond to the angular acceleration of the link + + + + + Force and torque applied to the link. The x, y, z components + of the pose correspond to the force applied to the link, and the roll, + pitch, yaw components correspond to the torque applied to the link + + + + + Collision state + + + Name of the collision + + + + + + diff --git a/sdf/1.12/logical_camera.sdf b/sdf/1.12/logical_camera.sdf new file mode 100644 index 000000000..de47703c0 --- /dev/null +++ b/sdf/1.12/logical_camera.sdf @@ -0,0 +1,19 @@ + + 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. + + + Near clipping distance of the view frustum + + + + Far clipping distance of the view frustum + + + + Aspect ratio of the near and far planes. This is the width divided by the height of the near or far planes. + + + + Horizontal field of view of the frustum, in radians. This is the angle between the frustum's vertex and the edges of the near or far plane. + + diff --git a/sdf/1.12/magnetometer.sdf b/sdf/1.12/magnetometer.sdf new file mode 100644 index 000000000..2f3bfeeee --- /dev/null +++ b/sdf/1.12/magnetometer.sdf @@ -0,0 +1,21 @@ + + These elements are specific to a Magnetometer sensor. + + + Parameters related to the body-frame X axis of the magnetometer + + + + + + Parameters related to the body-frame Y axis of the magnetometer + + + + + + Parameters related to the body-frame Z axis of the magnetometer + + + + \ No newline at end of file diff --git a/sdf/1.12/material.sdf b/sdf/1.12/material.sdf new file mode 100644 index 000000000..3459654e4 --- /dev/null +++ b/sdf/1.12/material.sdf @@ -0,0 +1,166 @@ + + + The material of the visual element. + + + Name of material from an installed script file. This will override the color element if the script exists. + + + URI of the material script file + + + + Name of the script within the script file + + + + + + + vertex, pixel, normal_map_object_space, normal_map_tangent_space + + + + filename of the normal map + + + + + Set render order for coplanar polygons. The higher value will be rendered on top of the other coplanar polygons + + + + If false, dynamic lighting will be disabled + + + + The ambient color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + The diffuse color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The specular color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The specular exponent of a material + + + + The emissive color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + If true, the mesh that this material is applied to will be rendered as double sided + + + + + 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. + + + PBR using the Metallic/Roughness workflow. + + + Filename of the diffuse/albedo map. + + + + Filename of the roughness map. + + + + Material roughness in the range of [0,1], where 0 represents a smooth surface and 1 represents a rough surface. This is the inverse of a specular map in a PBR specular workflow. + + + + Filename of the metalness map. + + + + Material metalness in the range of [0,1], where 0 represents non-metal and 1 represents raw metal + + + + Filename of the environment / reflection map, typically in the form of a cubemap + + + + Filename of the ambient occlusion map. The map defines the amount of ambient lighting on the surface. + + + + + The space that the normals are in. Values are: 'object' or 'tangent' + + + Filename of the normal map. The normals can be in the object space or tangent space as specified in the 'type' attribute + + + + Filename of the emissive map. + + + + + Index of the texture coordinate set to use. + + Filename of the light map. The light map is a prebaked light texture that is applied over the albedo map + + + + + + PBR using the Specular/Glossiness workflow. + + + Filename of the diffuse/albedo map. + + + + Filename of the specular map. + + + + Filename of the glossiness map. + + + + Material glossiness in the range of [0-1], where 0 represents a rough surface and 1 represents a smooth surface. This is the inverse of a roughness map in a PBR metal workflow. + + + + Filename of the environment / reflection map, typically in the form of a cubemap + + + + Filename of the ambient occlusion map. The map defines the amount of ambient lighting on the surface. + + + + + The space that the normals are in. Values are: 'object' or 'tangent' + + + Filename of the normal map. The normals can be in the object space or tangent space as specified in the 'type' attribute + + + + Filename of the emissive map. + + + + + Index of the texture coordinate set to use. + + Filename of the light map. The light map is a prebaked light texture that is applied over the albedo map + + + + + + + diff --git a/sdf/1.12/mesh_shape.sdf b/sdf/1.12/mesh_shape.sdf new file mode 100644 index 000000000..61bce76dd --- /dev/null +++ b/sdf/1.12/mesh_shape.sdf @@ -0,0 +1,20 @@ + + Mesh shape + + Mesh uri + + + + Use a named submesh. The submesh must exist in the mesh specified by the uri + + Name of the submesh within the parent mesh + + + Set to true to center the vertices of the submesh at 0,0,0. This will effectively remove any transformations on the submesh before the poses from parent links and models are applied. + + + + + Scaling factor applied to the mesh + + diff --git a/sdf/1.12/mimic.sdf b/sdf/1.12/mimic.sdf new file mode 100644 index 000000000..c70f9b065 --- /dev/null +++ b/sdf/1.12/mimic.sdf @@ -0,0 +1,37 @@ + + + Specifies a linear equality constraint between the position of two joint + axes. One joint axis is labeled as the leader and the other as the follower. + The joint axis containing a mimic tag is the follower, and the leader + is specified by the joint and axis attributes. + The multiplier, offset, and reference parameters determine the linear relationship + according to the following equation: + follower_position = multiplier * (leader_position - reference) + offset. + Note that the multiplier and offset parameters match the parameters of + the URDF mimic tag if the reference parameter is 0. + + + Name of the joint containing the leader axis, i.e. the axis to be mimicked + + + Name of the leader axis, i.e. the axis to be mimicked. + The only valid values are "axis" and "axis2", and "axis2" may only be + used if the leader joint has multiple axes. + + + + A parameter representing the ratio between changes in the + follower joint axis position relative to changes in the leader joint + axis position. It can be expressed as follows: + multiplier = (follower_position - offset) / (leader_position - reference) + + + + Offset to the follower position in the linear constraint. + + + Reference for the leader position before applying the + multiplier in the linear constraint. + + + diff --git a/sdf/1.12/model.sdf b/sdf/1.12/model.sdf new file mode 100644 index 000000000..57dc83a01 --- /dev/null +++ b/sdf/1.12/model.sdf @@ -0,0 +1,92 @@ + + + The model element defines a complete robot or any other physical object. + + + + The name of the model and its implicit frame. This name must be unique + among all elements defining frames within the same scope, i.e., it must + not match another //model, //frame, //joint, or //link within the same + scope. + + + + + + The name of the model's canonical link, to which the model's implicit + coordinate frame is attached. If unset or set to an empty string, the + first `/link` listed as a direct child of this model is chosen as the + canonical link. If the model has no direct `/link` children, it will + instead be attached to the first nested (or included) model's implicit + frame. + + + + 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. + + + + + If set to true, the model is immovable; i.e., a dynamics engine will not + update its position. This will also overwrite this model's `@canonical_link` + and instead attach the model's implicit frame to the world's implicit frame. + This holds even if this model is nested (or included) by another model + instead of being a direct child of `//world`. + + + + + If set to true, all links in the model will collide with each other (except those connected by a joint). Can be overridden by the link or collision element self_collide property. Two links within a model will collide if link1.self_collide OR link2.self_collide. Links connected by a joint will never collide. + + + + Allows a model to auto-disable, which is means the physics engine can skip updating the model when the model is at rest. This parameter is only used by models with no joints. + + + + + + + + + + + + Include resources from a URI. This can be used to nest models. The included resource can only contain one 'model' 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). + + + Merge the included nested model into the top model + + + + URI to a resource, such as a model + + + + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + The frame inside the included model whose pose will be set by the specified pose element. If this element is specified, the pose must be specified. + + + + + A nested model element + + A unique name for the model. This name must not match another nested model in the same level as this model. + + + + + If set to true, all links in the model will be affected by the wind. Can be overriden by the link wind property. + + + diff --git a/sdf/1.12/model_state.sdf b/sdf/1.12/model_state.sdf new file mode 100644 index 000000000..3fd296ff2 --- /dev/null +++ b/sdf/1.12/model_state.sdf @@ -0,0 +1,41 @@ + + + Model state + + + Name of the model + + + + Joint angle + + + Name of the joint + + + + + Index of the axis. + + + Angle of an axis + + + + + A nested model state element + + Name of the model. + + + + + + + + Scale for the 3 dimensions of the model. + + + + + diff --git a/sdf/1.12/navsat.sdf b/sdf/1.12/navsat.sdf new file mode 100644 index 000000000..8a8f1719b --- /dev/null +++ b/sdf/1.12/navsat.sdf @@ -0,0 +1,40 @@ + + These elements are specific to the NAVSAT sensor. + + + + Parameters related to NAVSAT position measurement. + + + + Noise parameters for horizontal position measurement, in units of meters. + + + + + + Noise parameters for vertical position measurement, in units of meters. + + + + + + + + Parameters related to NAVSAT position measurement. + + + + Noise parameters for horizontal velocity measurement, in units of meters/second. + + + + + + Noise parameters for vertical velocity measurement, in units of meters/second. + + + + + + diff --git a/sdf/1.12/noise.sdf b/sdf/1.12/noise.sdf new file mode 100644 index 000000000..ceeac5037 --- /dev/null +++ b/sdf/1.12/noise.sdf @@ -0,0 +1,43 @@ + + The properties of a sensor noise model. + + + + 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)) + + + + + For type "gaussian*", the mean of the Gaussian distribution from which + noise values are drawn. + + + + For type "gaussian*", the standard deviation of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian*", the mean of the Gaussian distribution from which bias values are drawn. + + + For type "gaussian*", the standard deviation of the Gaussian distribution from which bias values are drawn. + + + + For type "gaussian*", the standard deviation of the noise used to drive a process to model slow variations in a sensor bias. + + + + For type "gaussian*", the correlation time in seconds of the noise used to drive a process to model slow variations in a sensor bias. A typical value, when used, would be on the order of 3600 seconds (1 hour). + + + + + For type "gaussian_quantized", the precision of output signals. A value + of zero implies infinite precision / no quantization. + + + + diff --git a/sdf/1.12/particle_emitter.sdf b/sdf/1.12/particle_emitter.sdf new file mode 100755 index 000000000..d6a2fdf7e --- /dev/null +++ b/sdf/1.12/particle_emitter.sdf @@ -0,0 +1,120 @@ + + + A particle emitter that can be used to describe fog, smoke, and dust. + + + A unique name for the particle emitter. + + + + The type of a particle emitter. One of "box", "cylinder", "ellipsoid", or "point". + + + + True indicates that the particle emitter should generate particles when loaded + + + + The number of seconds the emitter is active. A value less than or equal to zero means infinite duration. + + + + + The size of the emitter where the particles are sampled. + Default value is (1, 1, 1). + Note that the interpretation of the emitter area varies + depending on the emmiter type: + - point: The area is ignored. + - box: The area is interpreted as width X height X depth. + - cylinder: The area is interpreted as the bounding box of the + cylinder. The cylinder is oriented along the Z-axis. + - ellipsoid: The area is interpreted as the bounding box of an + ellipsoid shaped area, i.e. a sphere or + squashed-sphere area. The parameters are again + identical to EM_BOX, except that the dimensions + describe the widest points along each of the axes. + + + + + The particle dimensions (width, height, depth). + + + + The number of seconds each particle will ’live’ for before being destroyed. This value must be greater than zero. + + + + The number of particles per second that should be emitted. + + + + Sets a minimum velocity for each particle (m/s). + + + + Sets a maximum velocity for each particle (m/s). + + + + Sets the amount by which to scale the particles in both x and y direction per second. + + + + + Sets the starting color for all particles emitted. + The actual color will be interpolated between this color + and the one set under color_end. + Color::White is the default color for the particles + unless a specific function is used. + To specify a color, RGB values should be passed in. + For example, to specify red, a user should enter: + 1 0 0 + Note that this function overrides the particle colors set + with color_range_image. + + + + + + Sets the end color for all particles emitted. + The actual color will be interpolated between this color + and the one set under color_start. + Color::White is the default color for the particles + unless a specific function is used (see color_start for + more information about defining custom colors with RGB + values). + Note that this function overrides the particle colors set + with color_range_image. + + + + + + Sets the path to the color image used as an affector. This affector modifies the color of particles in flight. The colors are taken from a specified image file. The range of color values begins from the left side of the image and moves to the right over the lifetime of the particle, therefore only the horizontal dimension of the image is used. Note that this function overrides the particle colors set with color_start and color_end. + + + + + + Topic used to update particle emitter properties at runtime. + The default topic is + /model/{model_name}/particle_emitter/{emitter_name} + Note that the emitter id and name may not be changed. + + + + + + This is used to determine the ratio of particles that will be detected + by sensors. Increasing the ratio means there is a higher chance of + particles reflecting and interfering with depth sensing, making the + emitter appear more dense. Decreasing the ratio decreases the chance + of particles reflecting and interfering with depth sensing, making it + appear less dense. + + + + + + diff --git a/sdf/1.12/physics.sdf b/sdf/1.12/physics.sdf new file mode 100644 index 000000000..f644ae9fd --- /dev/null +++ b/sdf/1.12/physics.sdf @@ -0,0 +1,238 @@ + + + The physics tag specifies the type and properties of the dynamics engine. + + + The name of this set of physics parameters. + + + + If true, this physics element is set as the default physics profile for the world. If multiple default physics elements exist, the first element marked as default is chosen. If no default physics element exists, the first physics element is chosen. + + + + The type of the dynamics engine. Current options are ode, bullet, simbody and dart. Defaults to ode if left unspecified. + + + + Maximum time step size at which every system in simulation can interact with the states of the world. (was physics.sdf's dt). + + + + + target simulation speedup factor, defined by ratio of simulation time to real-time. + + + + + Rate at which to update the physics engine (UpdatePhysics calls per real-time second). (was physics.sdf's update_rate). + + + + Maximum number of contacts allowed between two entities. This value can be over ridden by a max_contacts element in a collision element. + + + + DART specific physics properties + + + + One of the following types: pgs, dantzig. PGS stands for Projected Gauss-Seidel. + + + + Specify collision detector for DART to use. Can be dart, fcl, bullet or ode. + + + + + Simbody specific physics properties + + (Currently not used in simbody) The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Roughly the relative error of the system. + -LOG(accuracy) is roughly the number of significant digits. + + + Tolerable "slip" velocity allowed by the solver when static + friction is supposed to hold object in place. + + + 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 - d*vp + e_max = maximum COR = 1-d*vc, reached at v=vc + e = 0, v <= vc + = 1 - d*v, vc < v < vp + = e_min, v >= vp + + dissipation factor = d*min(v,vp) [compliant] + cor = e [rigid] + + Combining rule e = 0, e1==e2==0 + = 2*e1*e2/(e1+e2), otherwise]]> + + + + Default contact material stiffness + (force/dist or torque/radian). + + + dissipation coefficient to be used in compliant contact; + if not given it is (1-min_cor)/plastic_impact_velocity + + + + this is the COR to be used at high velocities for rigid + impacts; if not given it is 1 - dissipation*plastic_impact_velocity + + + + + smallest impact velocity at which min COR is reached; set + to zero if you want the min COR always to be used + + + + static friction (mu_s) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + dynamic friction (mu_d) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + viscous friction (mu_v) with units of (1/velocity) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + + for rigid impacts only, impact velocity at which + COR is set to zero; normally inherited from global default but can + be overridden here. Combining rule: use larger velocity + + + + This is the largest slip velocity at which + we'll consider a transition to stiction. Normally inherited + from a global default setting. For a continuous friction model + this is the velocity at which the max static friction force + is reached. Combining rule: use larger velocity + + + + + + + Bullet specific physics properties + + + + One of the following types: sequential_impulse only. + + + The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + Set the successive over-relaxation parameter. + + + + + Bullet constraint parameters. + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + + + + ODE specific physics properties + + + + One of the following types: world, quick + + + The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Number of threads to use for "islands" of disconnected models. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + Experimental parameter. + + + Set the successive over-relaxation parameter. + + + Flag to use threading to speed up position correction computation. + + + + Flag to enable dynamic rescaling of moment of inertia in constrained directions. + See gazebo pull request 1114 for the implementation of this feature. + https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-request/1114 + + + + + Name of ODE friction model to use. Valid values include: + + pyramid_model: (default) friction forces limited in two directions + in proportion to normal force. + box_model: friction forces limited to constant in two directions. + cone_model: friction force magnitude limited in proportion to normal force. + + See gazebo pull request 1522 for the implementation of this feature. + https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-request/1522 + https://github.com/osrf/gazebo/commit/968dccafdfbfca09c9b3326f855612076fed7e6f + + + + + + ODE constraint parameters. + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The maximum correcting velocities allowed when resolving contacts. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + + diff --git a/sdf/1.12/plane_shape.sdf b/sdf/1.12/plane_shape.sdf new file mode 100644 index 000000000..2a82be152 --- /dev/null +++ b/sdf/1.12/plane_shape.sdf @@ -0,0 +1,9 @@ + + Plane shape + + Normal direction for the plane. When a Plane is used as a geometry for a Visual or Collision object, then the normal is specified in the Visual or Collision frame, respectively. + + + Length of each side of the plane. Note that this property is meaningful only for visualizing the Plane, i.e., when the Plane is used as a geometry for a Visual object. The Plane has infinite size when used as a geometry for a Collision object. + + diff --git a/sdf/1.12/plugin.sdf b/sdf/1.12/plugin.sdf new file mode 100644 index 000000000..4564fe4fb --- /dev/null +++ b/sdf/1.12/plugin.sdf @@ -0,0 +1,13 @@ + + + A plugin is a dynamically loaded chunk of code. It can exist as a child of world, model, and sensor. + + A name for the plugin. + + + Name of the shared library to load. If the filename is not a full path name, the file will be searched for in the configuration paths. + + + This is a special element that should not be specified in an SDFormat file. It automatically copies child elements into the SDFormat element so that a plugin can access the data. + + diff --git a/sdf/1.12/polyline_shape.sdf b/sdf/1.12/polyline_shape.sdf new file mode 100644 index 000000000..665884354 --- /dev/null +++ b/sdf/1.12/polyline_shape.sdf @@ -0,0 +1,14 @@ + + Defines an extruded polyline shape + + + + A series of points that define the path of the polyline. + + + + + Height of the polyline + + + diff --git a/sdf/1.12/population.sdf b/sdf/1.12/population.sdf new file mode 100644 index 000000000..b14ad739c --- /dev/null +++ b/sdf/1.12/population.sdf @@ -0,0 +1,58 @@ + + + + The population element defines how and where a set of models will + be automatically populated in Gazebo. + + + + + A unique name for the population. This name must not match + another population in the world. + + + + + + + + The number of models to place. + + + + + Specifies the type of object distribution and its optional parameters. + + + + + Define how the objects will be placed in the specified region. + - random: Models placed at random. + - uniform: Models approximately placed in a 2D grid pattern with control + over the number of objects. + - grid: Models evenly placed in a 2D grid pattern. The number of objects + is not explicitly specified, it is based on the number of rows and + columns of the grid. + - linear-x: Models evently placed in a row along the global x-axis. + - linear-y: Models evently placed in a row along the global y-axis. + - linear-z: Models evently placed in a row along the global z-axis. + + + + + Number of rows in the grid. + + + Number of columns in the grid. + + + Distance between elements of the grid. + + + + + + + + + diff --git a/sdf/1.12/pose.sdf b/sdf/1.12/pose.sdf new file mode 100644 index 000000000..81bc62c3e --- /dev/null +++ b/sdf/1.12/pose.sdf @@ -0,0 +1,43 @@ + + + A pose (translation, rotation) expressed in the frame named by + @relative_to. The first three components (x, y, z) represent the position of + the element's origin (in the @relative_to frame). The rotation component + represents the orientation of the element as either a sequence of Euler + rotations (r, p, y), see http://sdformat.org/tutorials?tut=specify_pose, + or as a quaternion (x, y, z, w), where w is the real component. + + + + If specified, this pose is expressed in the named frame. The named frame + must be declared within the same scope (world/model) as the element that + has its pose specified by this tag. + + If missing, the pose is expressed in the frame of the parent XML element + of the element that contains the pose. For exceptions to this rule and + more details on the default behavior, see + http://sdformat.org/tutorials?tut=pose_frame_semantics. + + Note that @relative_to merely affects an element's initial pose and + does not affect the element's dynamic movement thereafter. + + New in v1.8: @relative_to may use frames of nested scopes. In this case, + the frame is specified using `::` as delimiter to define the scope of the + frame, e.g. `nested_model_A::nested_model_B::awesome_frame`. + + + + + 'euler_rpy' by default. Supported rotation formats are + 'euler_rpy', Euler angles representation in roll, pitch, yaw. The pose is expected to have 6 values. + 'quat_xyzw', Quaternion representation in x, y, z, w. The pose is expected to have 7 values. + + + + + + Whether or not the euler angles are in degrees, otherwise they will be interpreted as radians by default. + + + + diff --git a/sdf/1.12/projector.sdf b/sdf/1.12/projector.sdf new file mode 100644 index 000000000..ca8cc8fd3 --- /dev/null +++ b/sdf/1.12/projector.sdf @@ -0,0 +1,32 @@ + + + + Name of the projector + + + + Texture name + + + + Field of view + + + + + Near clip distance + + + + + far clip distance + + + + + + + + + + diff --git a/sdf/1.12/ray.sdf b/sdf/1.12/ray.sdf new file mode 100644 index 000000000..58cf68b39 --- /dev/null +++ b/sdf/1.12/ray.sdf @@ -0,0 +1,78 @@ + + These elements are specific to the ray (laser) sensor. + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + specifies range properties of each simulated ray + + The minimum distance for each ray. + + + The maximum distance for each ray. + + + Linear resolution of each ray. + + + + + The properties of the noise model that should be applied to generated scans + + The type of noise. Currently supported types are: "gaussian" (draw noise values independently for each beam from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + + + + + + diff --git a/sdf/1.12/rfid.sdf b/sdf/1.12/rfid.sdf new file mode 100644 index 000000000..61351dd8a --- /dev/null +++ b/sdf/1.12/rfid.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdf/1.12/rfidtag.sdf b/sdf/1.12/rfidtag.sdf new file mode 100644 index 000000000..55699dc08 --- /dev/null +++ b/sdf/1.12/rfidtag.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdf/1.12/road.sdf b/sdf/1.12/road.sdf new file mode 100644 index 000000000..172e48045 --- /dev/null +++ b/sdf/1.12/road.sdf @@ -0,0 +1,16 @@ + + + + Name of the road + + + + Width of the road + + + + A series of points that define the path of the road. + + + + diff --git a/sdf/1.12/root.sdf b/sdf/1.12/root.sdf new file mode 100644 index 000000000..94ecc8731 --- /dev/null +++ b/sdf/1.12/root.sdf @@ -0,0 +1,21 @@ + + SDFormat base element that can include one model, actor, light, or worlds. A user of multiple worlds could run parallel instances of simulation, or offer selection of a world at runtime. + + + + 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. + + + + + + + + + diff --git a/sdf/1.12/scene.sdf b/sdf/1.12/scene.sdf new file mode 100644 index 000000000..1428d2c92 --- /dev/null +++ b/sdf/1.12/scene.sdf @@ -0,0 +1,86 @@ + + + Specifies the look of the environment. + + + Color of the ambient light. + + + + Color of the background. + + + + Properties for the sky + + Time of day [0..24] + + + Sunrise time [0..24] + + + Sunset time [0..24] + + + + Information about clouds in the sky. + + Speed of the clouds + + + + Direction of the cloud movement + + + Density of clouds + + + + Average size of the clouds + + + + Ambient cloud color + + + + + The URI to a cubemap texture for a skybox. A .dds file is typically used for the cubemap. + + + + + Enable/disable shadows + + + + Controls fog + + Fog color + + + Fog type: constant, linear, quadratic + + + Distance to start of fog + + + Distance to end of fog + + + Density of fog + + + + + Enable/disable the grid + + + + Show/hide world origin indicator + + + diff --git a/sdf/1.12/schema/types.xsd b/sdf/1.12/schema/types.xsd new file mode 100644 index 000000000..3d1215ace --- /dev/null +++ b/sdf/1.12/schema/types.xsd @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdf/1.12/sensor.sdf b/sdf/1.12/sensor.sdf new file mode 100644 index 000000000..78954738b --- /dev/null +++ b/sdf/1.12/sensor.sdf @@ -0,0 +1,82 @@ + + + The sensor tag describes the type and properties of a sensor. + + + A unique name for the sensor. This name must not match another model in the model. + + + + The type name of the sensor. By default, SDFormat supports types + air_pressure, + air_speed, + 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. + + + + + If true the sensor will always be updated according to the update rate. + + + + The frequency at which the sensor data is generated. If left unspecified, the sensor will generate data every cycle. + + + + If true, the sensor is visualized in the GUI + + + + Name of the topic on which data is published. This is necessary for visualization + + + + If true, the sensor will publish performance metrics + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdf/1.12/sonar.sdf b/sdf/1.12/sonar.sdf new file mode 100644 index 000000000..0a048cda8 --- /dev/null +++ b/sdf/1.12/sonar.sdf @@ -0,0 +1,16 @@ + + These elements are specific to the sonar sensor. + + The sonar collision shape. Currently supported geometries are: "cone" and "sphere". + + + Minimum range + + + Max range + + + + Radius of the sonar cone at max range. This parameter is only used if geometry is "cone". + + diff --git a/sdf/1.12/sphere_shape.sdf b/sdf/1.12/sphere_shape.sdf new file mode 100644 index 000000000..73ad03e5d --- /dev/null +++ b/sdf/1.12/sphere_shape.sdf @@ -0,0 +1,6 @@ + + Sphere shape + + radius of the sphere + + diff --git a/sdf/1.12/spherical_coordinates.sdf b/sdf/1.12/spherical_coordinates.sdf new file mode 100644 index 000000000..978b15fbd --- /dev/null +++ b/sdf/1.12/spherical_coordinates.sdf @@ -0,0 +1,65 @@ + + + + Name of planetary surface model, used to determine the surface altitude + at a given latitude and longitude. The default is an ellipsoid model of + the earth based on the WGS-84 standard. It is used in Gazebo's GPS sensor + implementation. + + + + + + This field identifies how Gazebo world frame is aligned in Geographical + sense. The final Gazebo world frame orientation is obtained by rotating + a frame aligned with following notation by the field heading_deg. + Options are: + - ENU (East-North-Up) + + + + + Geodetic latitude at origin of gazebo reference frame, specified + in units of degrees. + + + + + + Longitude at origin of gazebo reference frame, specified in units + of degrees. + + + + + + Elevation of origin of gazebo reference frame, specified in meters. + + + + + + Equatorial axis of a custom surface type, specified in meters. + This is only required for custom surfaces. + + + + + + Polar axis of a custom surface type, specified in meters. + This is only required for custom surfaces. + + + + + + Heading offset of gazebo reference frame, measured as angle between + Gazebo world frame and the world_frame_orientation type. + The direction of rotation follows the right-hand rule, so a positive + angle indicates clockwise rotation (from east to north) when viewed from top-down. Note + that this is not consistent with compass heading convention. + The angle is specified in degrees. + + + + diff --git a/sdf/1.12/state.sdf b/sdf/1.12/state.sdf new file mode 100644 index 000000000..6a13e28bf --- /dev/null +++ b/sdf/1.12/state.sdf @@ -0,0 +1,41 @@ + + + + + Name of the world this state applies to + + + + Simulation time stamp of the state [seconds nanoseconds] + + + + Wall time stamp of the state [seconds nanoseconds] + + + + Real time stamp of the state [seconds nanoseconds] + + + + Number of simulation iterations. + + + + A list containing the entire description of entities inserted. + + + + + + A list of names of deleted entities/ + + The name of a deleted entity. + + + + + + + + diff --git a/sdf/1.12/surface.sdf b/sdf/1.12/surface.sdf new file mode 100644 index 000000000..a1631368d --- /dev/null +++ b/sdf/1.12/surface.sdf @@ -0,0 +1,245 @@ + + The surface parameters + + + + Bounciness coefficient of restitution, from [0...1], where 0=no bounciness. + + + Bounce capture velocity, below which effective coefficient of restitution is 0. + + + + + + + + Parameters for torsional friction + + + Torsional friction coefficient, unitless maximum ratio of + tangential stress to normal stress. + + + + + If this flag is true, + torsional friction is calculated using the "patch_radius" parameter. + If this flag is set to false, + "surface_radius" (R) and contact depth (d) + are used to compute the patch radius as sqrt(R*d). + + + + Radius of contact patch surface. + + + Surface radius on the point of contact. + + + Torsional friction parameters for ODE + + + Force dependent slip for torsional friction, + equivalent to inverse of viscous damping coefficient + with units of rad/s/(Nm). + A slip value of 0 is infinitely viscous. + + + + + + + ODE friction parameters + + + Coefficient of friction in first friction pyramid direction, + the unitless maximum ratio of force in first friction pyramid + direction to normal force. + + + + + Coefficient of friction in second friction pyramid direction, + the unitless maximum ratio of force in second friction pyramid + direction to normal force. + + + + + Unit vector specifying first friction pyramid direction in + collision-fixed reference frame. + If the friction pyramid model is in use, + and this value is set to a unit vector for one of the + colliding surfaces, + the ODE Collide callback function will align the friction pyramid directions + with a reference frame fixed to that collision surface. + If both surfaces have this value set to a vector of zeros, + the friction pyramid directions will be aligned with the world frame. + If this value is set for both surfaces, the behavior is undefined. + + + + + Force dependent slip in first friction pyramid direction, + equivalent to inverse of viscous damping coefficient + with units of m/s/N. + A slip value of 0 is infinitely viscous. + + + + + Force dependent slip in second friction pyramid direction, + equivalent to inverse of viscous damping coefficient + with units of m/s/N. + A slip value of 0 is infinitely viscous. + + + + + + + Coefficient of friction in first friction pyramid direction, + the unitless maximum ratio of force in first friction pyramid + direction to normal force. + + + + + Coefficient of friction in second friction pyramid direction, + the unitless maximum ratio of force in second friction pyramid + direction to normal force. + + + + + Unit vector specifying first friction pyramid direction in + collision-fixed reference frame. + If the friction pyramid model is in use, + and this value is set to a unit vector for one of the + colliding surfaces, + the friction pyramid directions will be aligned + with a reference frame fixed to that collision surface. + If both surfaces have this value set to a vector of zeros, + the friction pyramid directions will be aligned with the world frame. + If this value is set for both surfaces, the behavior is undefined. + + + + Coefficient of rolling friction + + + + + + + + Flag to disable contact force generation, while still allowing collision checks and contact visualization to occur. + + + Bitmask for collision filtering when collide_without_contact is on + + + + Bitmask for collision filtering. This will override collide_without_contact. Parsed as 16-bit unsigned integer. + + + + + + + + + Poisson's ratio is the unitless ratio between transverse and axial strain. + This value must lie between (-1, 0.5). Defaults to 0.3 for typical steel. + Note typical silicone elastomers have Poisson's ratio near 0.49 ~ 0.50. + + For reference, approximate values for Material:(Young's Modulus, Poisson's Ratio) + for some of the typical materials are: + Plastic: (1e8 ~ 3e9 Pa, 0.35 ~ 0.41), + Wood: (4e9 ~ 1e10 Pa, 0.22 ~ 0.50), + Aluminum: (7e10 Pa, 0.32 ~ 0.35), + Steel: (2e11 Pa, 0.26 ~ 0.31). + + + + + Young's Modulus in SI derived unit Pascal. + Defaults to -1. If value is less or equal to zero, + contact using elastic modulus (with Poisson's Ratio) is disabled. + + For reference, approximate values for Material:(Young's Modulus, Poisson's Ratio) + for some of the typical materials are: + Plastic: (1e8 ~ 3e9 Pa, 0.35 ~ 0.41), + Wood: (4e9 ~ 1e10 Pa, 0.22 ~ 0.50), + Aluminum: (7e10 Pa, 0.32 ~ 0.35), + Steel: (2e11 Pa, 0.26 ~ 0.31). + + + + + ODE contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + maximum contact correction velocity truncation term. + + + minimum allowable depth before contact correction impulse is applied + + + + Bullet contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + Similar to ODE's max_vel implementation. See http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + Similar to ODE's max_vel implementation. See http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + + + + + + soft contact pamameters based on paper: + http://www.cc.gatech.edu/graphics/projects/Sumit/homepage/papers/sigasia11/jain_softcontacts_siga11.pdf + + + This is variable k_v in the soft contacts paper. Its unit is N/m. + + + This is variable k_e in the soft contacts paper. Its unit is N/m. + + + Viscous damping of point velocity in body frame. Its unit is N/m/s. + + + Fraction of mass to be distributed among deformable nodes. + + + + + diff --git a/sdf/1.12/transceiver.sdf b/sdf/1.12/transceiver.sdf new file mode 100644 index 000000000..9f05b069d --- /dev/null +++ b/sdf/1.12/transceiver.sdf @@ -0,0 +1,34 @@ + + These elements are specific to a wireless transceiver. + + + Service set identifier (network name) + + + + Specifies the frequency of transmission in MHz + + + + Only a frequency range is filtered. Here we set the lower bound (MHz). + + + + + Only a frequency range is filtered. Here we set the upper bound (MHz). + + + + + Specifies the antenna gain in dBi + + + + Specifies the transmission power in dBm + + + + Mininum received signal power in dBm + + + diff --git a/sdf/1.12/visual.sdf b/sdf/1.12/visual.sdf new file mode 100644 index 000000000..b07f45025 --- /dev/null +++ b/sdf/1.12/visual.sdf @@ -0,0 +1,38 @@ + + + The visual properties of the link. This element specifies the shape of the object (box, cylinder, etc.) for visualization purposes. + + + Unique name for the visual element within the scope of the parent link. + + + + If true the visual will cast shadows. + + + + will be implemented in the future release. + + + + The amount of transparency( 0=opaque, 1 = fully transparent) + + + + + + + + Optional meta information for the visual. The information contained within this element should be used to provide additional feedback to an end user. + + + The layer in which this visual is displayed. The layer number is useful for programs, such as Gazebo, that put visuals in different layers for enhanced visualization. + + + + + + + + + diff --git a/sdf/1.12/world.sdf b/sdf/1.12/world.sdf new file mode 100644 index 000000000..6235e193b --- /dev/null +++ b/sdf/1.12/world.sdf @@ -0,0 +1,75 @@ + + The world element encapsulates an entire world description including: models, scene, physics, and plugins. + + + Unique name of the world + + + + Global audio properties. + + + Device to use for audio playback. A value of "default" will use the system's default audio device. Otherwise, specify a an audio device file" + + + + + The wind tag specifies the type and properties of the wind. + + + Linear velocity of the wind. + + + + + + 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). + + + Merge the included model into the top model. Only elements valid in 'world' are allowed in the included model + + + URI to a resource, such as a model + + + + Override the name of the included entity. + + + + Override the static value of the included entity. + + + + + + + The frame inside the included entity whose pose will be set by the specified pose element. If this element is specified, the pose must be specified. + + + + + The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + + + + + + + + + + + + + + + + diff --git a/sdf/CMakeLists.txt b/sdf/CMakeLists.txt index 10e789bfa..aec064bd3 100644 --- a/sdf/CMakeLists.txt +++ b/sdf/CMakeLists.txt @@ -9,6 +9,7 @@ add_subdirectory(1.8) add_subdirectory(1.9) add_subdirectory(1.10) add_subdirectory(1.11) +add_subdirectory(1.12) add_custom_target(schema) add_dependencies(schema schema1_11) diff --git a/sdf/embedSdf.py b/sdf/embedSdf.py index 733871d99..b0cd7991a 100644 --- a/sdf/embedSdf.py +++ b/sdf/embedSdf.py @@ -14,6 +14,7 @@ # The list of supported SDF specification versions. This will let us drop # versions without removing the directories. SUPPORTED_SDF_VERSIONS = [ + "1.12", "1.11", "1.10", "1.9", @@ -28,7 +29,7 @@ # The list of supported SDF conversions. This list includes versions that # a user can convert an existing SDF version to. -SUPPORTED_SDF_CONVERSIONS = ["1.11", "1.10", "1.9", "1.8", "1.7", "1.6", "1.5", "1.4", "1.3"] +SUPPORTED_SDF_CONVERSIONS = ["1.12", "1.11", "1.10", "1.9", "1.8", "1.7", "1.6", "1.5", "1.4", "1.3"] # whitespace indentation for C++ code INDENTATION = " " diff --git a/src/Root_TEST.cc b/src/Root_TEST.cc index d48382276..4bb518ad2 100644 --- a/src/Root_TEST.cc +++ b/src/Root_TEST.cc @@ -583,7 +583,7 @@ TEST(DOMRoot, CopyConstructor) auto testFrame1 = [](const sdf::Root &_root) { - EXPECT_EQ("1.11", _root.Version()); + EXPECT_EQ("1.12", _root.Version()); const sdf::World *world = _root.WorldByIndex(0); ASSERT_NE(nullptr, world);