[sdformat] 01/02: Imported Upstream version 2.2.0
Jose Luis Rivero
jrivero-guest at moszumanska.debian.org
Fri Nov 21 00:43:56 UTC 2014
This is an automated email from the git hooks/post-receive script.
jrivero-guest pushed a commit to branch master
in repository sdformat.
commit a0d4de932a7be6efe421ffc37bd1308ef5cf917b
Author: Jose Luis Rivero <jrivero at osrfoundation.org>
Date: Fri Nov 21 00:41:40 2014 +0000
Imported Upstream version 2.2.0
---
.hg_archival.txt | 6 +-
.hgtags | 1 +
CMakeLists.txt | 4 +-
sdf/1.4/physics.sdf | 7 ++
sdf/1.5/CMakeLists.txt | 2 +
sdf/1.5/camera.sdf | 22 ++++++
sdf/1.5/gui.sdf | 3 +-
sdf/1.5/magnetometer.sdf | 4 +
sdf/1.5/physics.sdf | 13 +++-
sdf/1.5/population.sdf | 60 +++++++++++++++
sdf/1.5/sensor.sdf | 18 ++++-
sdf/1.5/world.sdf | 2 +
src/parser_urdf.cc | 13 ++++
test/integration/CMakeLists.txt | 2 +
test/integration/force_torque_sensor.cc | 64 ++++++++++++++++
test/integration/force_torque_sensor.urdf | 54 +++++++++++++
test/integration/urdf_joint_parameters.cc | 82 ++++++++++++++++++++
test/integration/urdf_joint_parameters.urdf | 115 ++++++++++++++++++++++++++++
18 files changed, 464 insertions(+), 8 deletions(-)
diff --git a/.hg_archival.txt b/.hg_archival.txt
index b678e81..f33f8a9 100644
--- a/.hg_archival.txt
+++ b/.hg_archival.txt
@@ -1,5 +1,5 @@
repo: 17049bd77df5bd6cd56a76edba4a54afb5647740
-node: 2de443974f0b74f2a4e2c91f84e44cab0583d901
+node: 95b7b298de85c4bb7ee9e5e5a8e26a2efe5e42b5
branch: sdf_2.0
-latesttag: sdformat2_2.0.1
-latesttagdistance: 1
+latesttag: sdformat2_2.1.0
+latesttagdistance: 6
diff --git a/.hgtags b/.hgtags
index ea20239..1164c16 100644
--- a/.hgtags
+++ b/.hgtags
@@ -79,3 +79,4 @@ ded65a6bf12e2b13982d2b1b3c22d22b21be5fe2 sdformat2_2.0.1
1d27e7196bd0e0a1290d9986ae1dba004a31758b sdformat2_2.0.1
1d27e7196bd0e0a1290d9986ae1dba004a31758b sdformat2_2.0.1
d79259b26096295719cd65acc9ac07d68870fd47 sdformat2_2.0.1
+e1bb1bc7035660de317cf17da176e007f99c42c0 sdformat2_2.1.0
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 76c7cf5..0c1c157 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -28,8 +28,8 @@ string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
set (SDF_PROTOCOL_VERSION 1.5)
set (SDF_MAJOR_VERSION 2)
-set (SDF_MINOR_VERSION 0)
-set (SDF_PATCH_VERSION 1)
+set (SDF_MINOR_VERSION 2)
+set (SDF_PATCH_VERSION 0)
set (SDF_VERSION ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION})
set (SDF_VERSION_FULL ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}.${SDF_PATCH_VERSION})
diff --git a/sdf/1.4/physics.sdf b/sdf/1.4/physics.sdf
index 2e73c25..910b600 100644
--- a/sdf/1.4/physics.sdf
+++ b/sdf/1.4/physics.sdf
@@ -173,6 +173,13 @@
<element name="sor" type="double" default="1.3" required="1">
<description>Set the successive over-relaxation parameter.</description>
</element>
+ <element name="use_dynamic_moi_rescaling" type="bool" default="0" required="1">
+ <description>
+ Flag to enable dynamic rescaling of moment of inertia in constrained directions.
+ See gazebo pull request 1114 for the implementation of this feature.
+ https://bitbucket.org/osrf/gazebo/pull-request/1114
+ </description>
+ </element>
</element> <!-- End Solver -->
<element name="constraints" required="1">
diff --git a/sdf/1.5/CMakeLists.txt b/sdf/1.5/CMakeLists.txt
index bd1e3fb..b125d90 100644
--- a/sdf/1.5/CMakeLists.txt
+++ b/sdf/1.5/CMakeLists.txt
@@ -20,6 +20,7 @@ set (sdfs
joint.sdf
light.sdf
link.sdf
+ magnetometer.sdf
material.sdf
mesh_shape.sdf
model.sdf
@@ -28,6 +29,7 @@ set (sdfs
plane_shape.sdf
plugin.sdf
polyline_shape.sdf
+ population.sdf
projector.sdf
ray.sdf
rfidtag.sdf
diff --git a/sdf/1.5/camera.sdf b/sdf/1.5/camera.sdf
index 5ae23cb..d3b87c1 100644
--- a/sdf/1.5/camera.sdf
+++ b/sdf/1.5/camera.sdf
@@ -68,4 +68,26 @@
</element>
</element> <!-- End Noise -->
+ <element name="distortion" required="0">
+ <description>Lens distortion to be applied to camera images. See http://en.wikipedia.org/wiki/Distortion_(optics)#Software_correction</description>
+ <element name="k1" type="double" default="0.0" required="0">
+ <description>The radial distortion coefficient k1</description>
+ </element>
+ <element name="k2" type="double" default="0.0" required="0">
+ <description>The radial distortion coefficient k2</description>
+ </element>
+ <element name="k3" type="double" default="0.0" required="0">
+ <description>The radial distortion coefficient k3</description>
+ </element>
+ <element name="p1" type="double" default="0.0" required="0">
+ <description>The tangential distortion coefficient p1</description>
+ </element>
+ <element name="p2" type="double" default="0.0" required="0">
+ <description>The tangential distortion coefficient p2</description>
+ </element>
+ <element name="center" type="vector2d" default="0.5 0.5" required="0">
+ <description>The distortion center or principal point</description>
+ </element>
+ </element> <!-- End Distortion -->
+
</element> <!-- End Camera -->
diff --git a/sdf/1.5/gui.sdf b/sdf/1.5/gui.sdf
index 8300090..6bfc5a9 100644
--- a/sdf/1.5/gui.sdf
+++ b/sdf/1.5/gui.sdf
@@ -4,6 +4,8 @@
<description></description>
</attribute>
+ <include filename="plugin.sdf" required="*"/>
+
<element name="camera" required="0">
<description> </description>
@@ -11,7 +13,6 @@
<description></description>
</attribute>
-
<element name="view_controller" type="string" default="orbit" required="0">
<description></description>
</element>
diff --git a/sdf/1.5/magnetometer.sdf b/sdf/1.5/magnetometer.sdf
new file mode 100644
index 0000000..8cce8d7
--- /dev/null
+++ b/sdf/1.5/magnetometer.sdf
@@ -0,0 +1,4 @@
+<element name="magnetometer" required="0">
+ <description>These elements are specific to a Magnetometer sensor.</description>
+ <include filename="noise.sdf" required="0"/>
+</element>
\ No newline at end of file
diff --git a/sdf/1.5/physics.sdf b/sdf/1.5/physics.sdf
index 2e73c25..7f4e4ee 100644
--- a/sdf/1.5/physics.sdf
+++ b/sdf/1.5/physics.sdf
@@ -26,9 +26,13 @@
</element>
<element name="gravity" type="vector3" default="0 0 -9.8" required="1">
- <description>The gravity vector</description>
+ <description>The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag.</description>
</element> <!-- End Gravity -->
+ <element name="magnetic_field" type="vector3" default="5.5645e-6 22.8758e-6 -42.3884e-6" required="1">
+ <description>The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag.</description>
+ </element> <!-- End Magnetic -->
+
<element name="simbody" required="0">
<description>Simbody specific physics properties</description>
<element name="min_step_size" type="double" default="0.0001" required="0">
@@ -173,6 +177,13 @@
<element name="sor" type="double" default="1.3" required="1">
<description>Set the successive over-relaxation parameter.</description>
</element>
+ <element name="use_dynamic_moi_rescaling" type="bool" default="0" required="1">
+ <description>
+ Flag to enable dynamic rescaling of moment of inertia in constrained directions.
+ See gazebo pull request 1114 for the implementation of this feature.
+ https://bitbucket.org/osrf/gazebo/pull-request/1114
+ </description>
+ </element>
</element> <!-- End Solver -->
<element name="constraints" required="1">
diff --git a/sdf/1.5/population.sdf b/sdf/1.5/population.sdf
new file mode 100644
index 0000000..c1ee322
--- /dev/null
+++ b/sdf/1.5/population.sdf
@@ -0,0 +1,60 @@
+<!-- Population -->
+<element name="population" required="*">
+ <description>
+ The population element defines how and where a set of models will
+ be automatically populated in Gazebo.
+ </description>
+
+ <attribute name="name" type="string" default="__default__" required="1">
+ <description>
+ A unique name for the population. This name must not match
+ another population in the world.
+ </description>
+ </attribute>
+
+ <element name="pose" type="pose" default="0 0 0 0 0 0" required="0">
+ <description>The reference frame of the population's region.</description>
+ </element><!-- End Pose -->
+
+ <include filename="box_shape.sdf" required="0"/>
+ <include filename="cylinder_shape.sdf" required="0"/>
+
+ <element name="model_count" type="int" default="1" required="1">
+ <description>The number of models to place.</description>
+ </element><!-- End Model_count -->
+
+ <element name="distribution" required="1">
+ <description>
+ Specifies the type of object distribution and its optional parameters.
+ </description>
+
+ <element name="type" type="string" default="random" required="1">
+ <description>
+ 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.
+ </description>
+ </element><!-- End Type -->
+
+ <element name="rows" type="int" default="1" required="0">
+ <description>Number of rows in the grid.</description>
+ </element><!-- End Rows -->
+ <element name="cols" type="int" default="1" required="0">
+ <description>Number of columns in the grid.</description>
+ </element><!-- End Columns -->
+ <element name="step" type="vector3" default="0.5 0.5 0" required="0">
+ <description>Distance between elements of the grid.</description>
+ </element><!-- End Step -->
+
+ </element><!-- End Distribution -->
+
+ <include filename="model.sdf" required="1"/>
+
+</element> <!-- End Population -->
\ No newline at end of file
diff --git a/sdf/1.5/sensor.sdf b/sdf/1.5/sensor.sdf
index a82ce9c..324a04a 100644
--- a/sdf/1.5/sensor.sdf
+++ b/sdf/1.5/sensor.sdf
@@ -7,7 +7,22 @@
</attribute>
<attribute name="type" type="string" default="__default__" required="1">
- <description>The type name of the sensor. By default, SDF supports types camera, depth, multicamera, contact, gps, imu, ir and ray.</description>
+ <description>The type name of the sensor. By default, SDF supports types
+ camera,
+ contact,
+ depth,
+ force_torque,
+ gps,
+ gpu_ray,
+ imu,
+ magnetometer,
+ multicamera,
+ ray,
+ rfid,
+ rfidtag,
+ sonar,
+ wireless_receiver, and
+ wireless_transmitter.</description>
</attribute>
<element name="always_on" type="bool" default="false" required="0">
@@ -35,6 +50,7 @@
<include filename="contact.sdf" required="0"/>
<include filename="gps.sdf" required="0"/>
<include filename="imu.sdf" required="0"/>
+ <include filename="magnetometer.sdf" required="0"/>
<include filename="ray.sdf" required="0"/>
<include filename="rfid.sdf" required="0"/>
<include filename="rfidtag.sdf" required="0"/>
diff --git a/sdf/1.5/world.sdf b/sdf/1.5/world.sdf
index b043f09..9d20a03 100644
--- a/sdf/1.5/world.sdf
+++ b/sdf/1.5/world.sdf
@@ -27,4 +27,6 @@
<include filename="spherical_coordinates.sdf" required="0"/>
<include filename="state.sdf" required="*"/>
+ <include filename="population.sdf" required="*"/>
+
</element> <!-- End World -->
diff --git a/src/parser_urdf.cc b/src/parser_urdf.cc
index 01e0783..5db7bf8 100644
--- a/src/parser_urdf.cc
+++ b/src/parser_urdf.cc
@@ -1617,6 +1617,14 @@ void InsertSDFExtensionJoint(TiXmlElement *_elem,
physics->LinkEndChild(physicsOde);
if (newPhysics)
_elem->LinkEndChild(physics);
+
+ // insert all additional blobs into joint
+ for (std::vector<TiXmlElementPtr>::iterator
+ blobIt = (*ge)->blobs.begin();
+ blobIt != (*ge)->blobs.end(); ++blobIt)
+ {
+ _elem->LinkEndChild((*blobIt)->Clone());
+ }
}
}
}
@@ -2468,6 +2476,7 @@ void CreateJoint(TiXmlElement *_root,
AddKeyValue(jointAxisLimit, "lower", "0");
AddKeyValue(jointAxisLimit, "upper", "0");
AddKeyValue(jointAxisDynamics, "damping", "0");
+ AddKeyValue(jointAxisDynamics, "friction", "0");
}
else
{
@@ -2481,8 +2490,12 @@ void CreateJoint(TiXmlElement *_root,
AddKeyValue(jointAxis, "xyz",
Values2str(3, rotatedJointAxisArray));
if (_link->parent_joint->dynamics)
+ {
AddKeyValue(jointAxisDynamics, "damping",
Values2str(1, &_link->parent_joint->dynamics->damping));
+ AddKeyValue(jointAxisDynamics, "friction",
+ Values2str(1, &_link->parent_joint->dynamics->friction));
+ }
if (g_enforceLimits && _link->parent_joint->limits)
{
diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt
index bbb320b..9939024 100644
--- a/test/integration/CMakeLists.txt
+++ b/test/integration/CMakeLists.txt
@@ -4,9 +4,11 @@ set(tests
audio.cc
cfm_damping_implicit_spring_damper.cc
fixed_joint_reduction.cc
+ force_torque_sensor.cc
joint_axis_frame.cc
plugin_attribute.cc
provide_feedback.cc
+ urdf_joint_parameters.cc
)
link_directories(${PROJECT_BINARY_DIR}/test)
diff --git a/test/integration/force_torque_sensor.cc b/test/integration/force_torque_sensor.cc
new file mode 100644
index 0000000..0cb2c62
--- /dev/null
+++ b/test/integration/force_torque_sensor.cc
@@ -0,0 +1,64 @@
+/*
+ * Copyright 2013 Open Source Robotics Foundation
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+*/
+
+#include <gtest/gtest.h>
+#include <boost/filesystem.hpp>
+#include <map>
+#include "sdf/sdf.hh"
+
+#include "test_config.h"
+
+const std::string SDF_TEST_FILE = std::string(PROJECT_SOURCE_PATH)
+ + "/test/integration/force_torque_sensor.urdf";
+
+/////////////////////////////////////////////////
+TEST(SDFParser, ForceTorqueSensorTest)
+{
+ char *pathCStr = getenv("SDF_PATH");
+ boost::filesystem::path path = PROJECT_SOURCE_PATH;
+ path = path / "sdf" / SDF_VERSION;
+ setenv("SDF_PATH", path.string().c_str(), 1);
+
+ sdf::SDFPtr robot(new sdf::SDF());
+ sdf::init(robot);
+ ASSERT_TRUE(sdf::readFile(SDF_TEST_FILE, robot));
+ if (pathCStr)
+ {
+ setenv("SDF_PATH", pathCStr, 1);
+ }
+ else
+ {
+ unsetenv("SDF_PATH");
+ }
+
+ sdf::ElementPtr model = robot->root->GetElement("model");
+ for (sdf::ElementPtr joint = model->GetElement("joint"); joint;
+ joint = joint->GetNextElement("joint"))
+ {
+ std::string jointName = joint->Get<std::string>("name");
+ if (jointName == "joint_1")
+ {
+ // Sensor tag was specified
+ EXPECT_TRUE(joint->HasElement("sensor"));
+ }
+ else if (jointName == "joint_2")
+ {
+ // No sensor tag was specified
+ EXPECT_FALSE(joint->HasElement("sensor"));
+ }
+ }
+}
diff --git a/test/integration/force_torque_sensor.urdf b/test/integration/force_torque_sensor.urdf
new file mode 100644
index 0000000..4b96add
--- /dev/null
+++ b/test/integration/force_torque_sensor.urdf
@@ -0,0 +1,54 @@
+<?xml version="1.0" ?>
+<robot name="force_torque_sensor_test">
+
+ <link name="base_link">
+ <inertial>
+ <mass value="1"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ </link>
+
+ <joint name="joint_1" type="revolute">
+ <parent link="base_link"/>
+ <child link="link_1"/>
+ <axis xyz="0 0 1"/>
+ <limit effort="1" lower="-1" upper="1" velocity="1"/>
+ <dynamics damping="1"/>
+ </joint>
+
+ <link name="link_1">
+ <inertial>
+ <mass value="1"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ </link>
+
+ <joint name="joint_2" type="revolute">
+ <parent link="base_link"/>
+ <child link="link_2"/>
+ <axis xyz="0 0 1"/>
+ <limit effort="1" lower="-1" upper="1" velocity="1"/>
+ <dynamics damping="1"/>
+ </joint>
+
+ <link name="link_2">
+ <inertial>
+ <mass value="1"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ </link>
+
+ <gazebo reference="joint_1">
+ <provideFeedback>true</provideFeedback>
+ <sensor name="gzft_sensor" type="force_torque">
+ <always_on>1</always_on>
+ <update_rate>100.0</update_rate>
+ <visualize>1</visualize>
+ <force_torque>
+ <frame>child</frame>
+ </force_torque>
+ </sensor>
+ </gazebo>
+
+</robot>
+
diff --git a/test/integration/urdf_joint_parameters.cc b/test/integration/urdf_joint_parameters.cc
new file mode 100644
index 0000000..255f77e
--- /dev/null
+++ b/test/integration/urdf_joint_parameters.cc
@@ -0,0 +1,82 @@
+/*
+ * Copyright 2014 Open Source Robotics Foundation
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+*/
+
+#include <gtest/gtest.h>
+#include <map>
+#include <boost/filesystem.hpp>
+#include "sdf/sdf.hh"
+
+#include "test_config.h"
+
+const std::string SDF_TEST_FILE = std::string(PROJECT_SOURCE_PATH)
+ + "/test/integration/urdf_joint_parameters.urdf";
+
+/////////////////////////////////////////////////
+TEST(SDFParser, JointAxisParameters)
+{
+ char *pathCStr = getenv("SDF_PATH");
+ boost::filesystem::path path = PROJECT_SOURCE_PATH;
+ path = path / "sdf" / SDF_VERSION;
+ setenv("SDF_PATH", path.string().c_str(), 1);
+
+ sdf::SDFPtr robot(new sdf::SDF());
+ sdf::init(robot);
+ ASSERT_TRUE(sdf::readFile(SDF_TEST_FILE, robot));
+ if (pathCStr)
+ {
+ setenv("SDF_PATH", pathCStr, 1);
+ }
+ else
+ {
+ unsetenv("SDF_PATH");
+ }
+
+ sdf::ElementPtr model = robot->root->GetElement("model");
+
+ ASSERT_TRUE(model->HasElement("joint"));
+ unsigned int bitmask = 0;
+ for (sdf::ElementPtr joint = model->GetElement("joint"); joint;
+ joint = joint->GetNextElement("joint"))
+ {
+ std::string jointName = joint->Get<std::string>("name");
+
+ double value = -1.0;
+ if (jointName == "jointw0")
+ {
+ bitmask |= 0x1;
+ value = 0.0;
+ }
+ else if (jointName == "joint01")
+ {
+ bitmask |= 0x2;
+ value = 1.0;
+ }
+ else
+ {
+ continue;
+ }
+ ASSERT_TRUE(joint->HasElement("axis"));
+ sdf::ElementPtr axis = joint->GetElement("axis");
+ ASSERT_TRUE(axis->HasElement("dynamics"));
+ sdf::ElementPtr dynamics = axis->GetElement("dynamics");
+ ASSERT_TRUE(dynamics->HasElement("damping"));
+ ASSERT_TRUE(dynamics->HasElement("friction"));
+ EXPECT_DOUBLE_EQ(value, dynamics->Get<double>("damping"));
+ EXPECT_DOUBLE_EQ(value, dynamics->Get<double>("friction"));
+ }
+ EXPECT_EQ(bitmask, 0x3u);
+}
diff --git a/test/integration/urdf_joint_parameters.urdf b/test/integration/urdf_joint_parameters.urdf
new file mode 100644
index 0000000..e33fb28
--- /dev/null
+++ b/test/integration/urdf_joint_parameters.urdf
@@ -0,0 +1,115 @@
+<?xml version="1.0" ?>
+<robot name="urdf_joint_parameters">
+
+ <link name="world"/>
+
+ <joint name="jointw0" type="continuous">
+ <origin rpy="0 0 1.57079632679" xyz="0 0 1.0"/>
+ <axis xyz="1 0 0"/> <!-- in child (link1) frame -->
+ <parent link="world"/>
+ <child link="link0"/>
+ <dynamics damping="0.0" friction="0.0" />
+ </joint>
+
+ <link name="link0">
+ <inertial>
+ <mass value="1000"/>
+ <origin rpy="0 0 0" xyz="0 0 -0.5"/>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ </inertial>
+ <visual>
+ <geometry>
+ <box size="0.1 0.1 1.0"/>
+ </geometry>
+ <origin rpy="0 0 0" xyz="0 0 -0.5"/>
+ </visual>
+ </link>
+
+ <joint name="joint01" type="continuous">
+ <origin rpy="0 0 1.57079632679" xyz="0 0 -1"/>
+ <axis xyz="1 0 0"/> <!-- in child (link1) frame -->
+ <parent link="link0"/>
+ <child link="link1"/>
+ <dynamics damping="1.0" friction="1.0" />
+ </joint>
+
+ <link name="link1">
+ <inertial>
+ <mass value="100"/>
+ <origin rpy="1 3 4" xyz="0 -1.5 0"/>
+ <inertia ixx="2" ixy="0" ixz="0" iyy="3" iyz="0" izz="4"/>
+ </inertial>
+ <visual>
+ <geometry>
+ <box size="0.2 3.0 0.2"/>
+ </geometry>
+ <origin rpy="0 0 0" xyz="0 -1.5 0"/>
+ </visual>
+ </link>
+
+ <joint name="joint12" type="revolute">
+ <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 -3.0 0.0"/>
+ <axis xyz="0 1 0"/> <!-- in child (link1) frame -->
+ <limit lower="0" upper="0" velocity="1000" effort="10000"/>
+ <parent link="link1"/>
+ <child link="link2"/>
+ </joint>
+
+ <link name="link2">
+ <inertial>
+ <mass value="200"/>
+ <origin rpy="2 -3 -1.57079632679" xyz="0.2 0.4 1.0"/>
+ <inertia ixx="5" ixy="0" ixz="0" iyy="6" iyz="0" izz="7"/>
+ </inertial>
+ <visual>
+ <geometry>
+ <box size="0.3 0.3 2.0"/>
+ </geometry>
+ <origin rpy="0 0 0" xyz="0 0 1.0"/>
+ </visual>
+ </link>
+
+ <joint name="joint23" type="revolute">
+ <origin rpy="-1.57079632679 0 -1.57079632679" xyz="-0.5 0.5 2.5"/>
+ <axis xyz="0 1 0"/> <!-- in child (link1) frame -->
+ <limit lower="0" upper="0" velocity="1000" effort="10000"/>
+ <parent link="link2"/>
+ <child link="link3"/>
+ </joint>
+
+ <link name="link3">
+ <inertial>
+ <mass value="400"/>
+ <origin rpy="2 3 4" xyz="0.1 0.2 0.3"/>
+ <inertia ixx="8" ixy="0" ixz="0" iyy="9" iyz="0" izz="10"/>
+ </inertial>
+ <visual>
+ <geometry>
+ <box size="0.3 0.4 0.5"/>
+ </geometry>
+ <origin rpy="2 3 4" xyz="0.1 0.2 0.3"/>
+ </visual>
+ </link>
+
+ <joint name="joint01a" type="continuous">
+ <origin rpy="0 0 1.57079632679" xyz="0 0 -1"/>
+ <axis xyz="1 0 0"/> <!-- in child (link1) frame -->
+ <parent link="link0"/>
+ <child link="link1a"/>
+ </joint>
+
+ <link name="link1a">
+ <inertial>
+ <mass value="100"/>
+ <origin rpy="1 3 4" xyz="0 -1.5 0"/>
+ <inertia ixx="2" ixy="0" ixz="0" iyy="3" iyz="0" izz="4"/>
+ </inertial>
+ <visual>
+ <geometry>
+ <box size="0.2 3.0 0.2"/>
+ </geometry>
+ <origin rpy="0 0 0" xyz="0 -1.5 0"/>
+ </visual>
+ </link>
+
+</robot>
--
Alioth's /usr/local/bin/git-commit-notice on /srv/git.debian.org/git/debian-science/packages/sdformat.git
More information about the debian-science-commits
mailing list