From b8a6ff53eea0005cbd388fcad7c62e0ce63c0ee4 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 15 Jul 2020 11:25:25 -0700 Subject: [PATCH 001/152] Initial urdf parser plugin that parses sdformat Lots of TODOs Signed-off-by: Shane Loretz Signed-off-by: Shane Loretz --- CMakeLists.txt | 68 +++++ include/sdformat_urdf/sdformat_urdf.hpp | 33 +++ package.xml | 33 +++ sdformat_urdf_plugin.xml | 8 + src/sdformat_urdf.cpp | 324 ++++++++++++++++++++++++ src/sdformat_urdf_plugin.cpp | 58 +++++ 6 files changed, 524 insertions(+) create mode 100644 CMakeLists.txt create mode 100644 include/sdformat_urdf/sdformat_urdf.hpp create mode 100644 package.xml create mode 100644 sdformat_urdf_plugin.xml create mode 100644 src/sdformat_urdf.cpp create mode 100644 src/sdformat_urdf_plugin.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 00000000..808b44e1 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,68 @@ +cmake_minimum_required(VERSION 3.5) + +project(sdformat_urdf) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual) +endif() + +find_package(ament_cmake_ros REQUIRED) + +find_package(pluginlib REQUIRED) +find_package(rcutils REQUIRED) +find_package(sdformat9 REQUIRED) +find_package(urdfdom_headers REQUIRED) +find_package(urdf_parser_plugin REQUIRED) + +# Add sdformat_urdf shared library +add_library(sdformat_urdf SHARED + src/sdformat_urdf.cpp +) +target_link_libraries(sdformat_urdf + PUBLIC + sdformat9::sdformat9 +) +target_include_directories(sdformat_urdf + PUBLIC + "$" + "$" + ${urdfdom_headers_INCLUDE_DIRS} +) + +# Add sdformat_urdf_plugin module library +add_library(sdformat_urdf_plugin MODULE + src/sdformat_urdf_plugin.cpp +) +target_link_libraries(sdformat_urdf_plugin PUBLIC + sdformat_urdf +) +ament_target_dependencies(sdformat_urdf_plugin PUBLIC + "pluginlib" + "rcutils" + "urdf_parser_plugin" +) + +ament_export_dependencies(urdfdom_headers) +ament_export_dependencies(sdformat9) + +install(TARGETS sdformat_urdf sdformat_urdf_plugin + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install( + DIRECTORY include/ + DESTINATION include +) + +install(TARGETS sdformat_urdf EXPORT sdformat_urdf-export) +ament_export_targets(sdformat_urdf-export) + +pluginlib_export_plugin_description_file(urdf_parser_plugin "sdformat_urdf_plugin.xml") + +ament_package() diff --git a/include/sdformat_urdf/sdformat_urdf.hpp b/include/sdformat_urdf/sdformat_urdf.hpp new file mode 100644 index 00000000..e434bc02 --- /dev/null +++ b/include/sdformat_urdf/sdformat_urdf.hpp @@ -0,0 +1,33 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 + +#include +#include +#include + +namespace sdformat_urdf { +/// \brief Parse an SDFormat XML string and return URDF C++ structures +urdf::ModelInterfaceSharedPtr +parse(const std::string & data, sdf::Errors & errors); + +/// \brief Convert SDFormat C++ structures to URDF C++ structures +urdf::ModelInterfaceSharedPtr +sdf_to_urdf(const sdf::Root & sdf_dom, sdf::Errors & errors); + +/// \brief Convert SDFormat Model to URDF Model +urdf::ModelInterfaceSharedPtr +convert_model(const sdf::Model & sdf_model, sdf::Errors & errors); +} // namespace sdformat_urdf diff --git a/package.xml b/package.xml new file mode 100644 index 00000000..32e11304 --- /dev/null +++ b/package.xml @@ -0,0 +1,33 @@ + + + sdformat_urdf + 0.1.0 + + URDF plugin to parse SDFormat XML into URDF C++ structures. + + + Shane Loretz + Shane Loretz + + Apache 2.0 + + https://github.com/ros/sdformat_urdf + https://github.com/ros/sdformat_urdf/issues + + ament_cmake_ros + ament_cmake_ros + + urdf + + liburdfdom-headers-dev + pluginlib + urdf + urdf_parser_plugin + + urdf + urdf_parser_plugin + + + ament_cmake + + diff --git a/sdformat_urdf_plugin.xml b/sdformat_urdf_plugin.xml new file mode 100644 index 00000000..a1b18e3f --- /dev/null +++ b/sdformat_urdf_plugin.xml @@ -0,0 +1,8 @@ + + + + + Parse models as URDF from SDFormat XML. + + + diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp new file mode 100644 index 00000000..8c1ff976 --- /dev/null +++ b/src/sdformat_urdf.cpp @@ -0,0 +1,324 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 "sdformat_urdf/sdformat_urdf.hpp" + +#include +#include +#include + +#include +#include +#include + +namespace sdformat_urdf { +/// \brief Convert SDFormat Link to URDF Link +urdf::LinkSharedPtr +convert_link(const sdf::Link & sdf_link, sdf::Errors & errors); + +/// \brief Convert SDFormat Joint to URDF Joint +urdf::JointSharedPtr +convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors); + +urdf::Pose +convert_pose(const ignition::math::Pose3d & sdf_pose); +} // namespace sdformat_urdf + +urdf::ModelInterfaceSharedPtr +sdformat_urdf::parse(const std::string & data, sdf::Errors & errors) +{ + auto sdf_dom = std::make_shared(); + errors = sdf_dom->LoadSdfString(data); + if (sdf_dom) { + return sdformat_urdf::sdf_to_urdf(*sdf_dom, errors); + } + return nullptr; +} + + +urdf::ModelInterfaceSharedPtr +sdformat_urdf::sdf_to_urdf(const sdf::Root & sdf_dom, sdf::Errors & errors) +{ + if (sdf_dom.WorldCount()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "SDFormat xml has a world; but only a single model is supported"); + return nullptr; + } + if (1u != sdf_dom.ModelCount()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "SDFormat xml has multiple models; but only a single model is supported"); + return nullptr; + } + + return convert_model(*sdf_dom.ModelByIndex(0), errors); +} + +urdf::ModelInterfaceSharedPtr +sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) +{ + urdf::ModelInterfaceSharedPtr urdf_model = std::make_shared(); + + // copy name + urdf_model->name_ = sdf_model.Name(); + + // create matching links + for (uint64_t l = 0; l < sdf_model.LinkCount(); ++l) { + const sdf::Link * sdf_link = sdf_model.LinkByIndex(l); + + if (!sdf_link) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get sdf link"); + return nullptr; + } + + auto pair = urdf_model->links_.emplace(sdf_link->Name(), convert_link(*sdf_link, errors)); + + if (!pair.second) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to create element in links map"); + return nullptr; + } + + const std::shared_ptr & urdf_link = pair.first->second; + + if (!urdf_link) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to convert sdf::link [" + sdf_link->Name() + "] to urdf::Link"); + return nullptr; + } + } + + // sdf canonical link -> urdf root link + const sdf::Link * sdf_canonical_link = sdf_model.CanonicalLink(); + if (!sdf_canonical_link) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get sdf canonical link"); + return nullptr; + } + auto iter = urdf_model->links_.find(sdf_canonical_link->Name()); + if (iter == urdf_model->links_.end()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to find sdf canonical link [" + sdf_canonical_link->Name() + "]"); + return nullptr; + } + urdf_model->root_link_ = iter->second; + + // create matching joints + for (uint64_t j = 0; j < sdf_model.JointCount(); ++j) { + const sdf::Joint * sdf_joint = sdf_model.JointByIndex(j); + + if (!sdf_joint) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get sdf joint"); + return nullptr; + } + + auto pair = urdf_model->joints_.emplace(sdf_joint->Name(), convert_joint(*sdf_joint, errors)); + + if (!pair.second) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to create element in joints map"); + return nullptr; + } + + const std::shared_ptr & urdf_joint = pair.first->second; + if (!urdf_joint) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to convert sdf::joint [" + sdf_joint->Name() + "] to urdf::Joint"); + return nullptr; + } + } + + // Start with root link (sdf canonical frame) and recurse this function: + // + // TODO what about coordinate frames? + // Link pose in URDF is relative to link reference frame + // Link reference frame is parent joint - joint in which this frame is the child link + // Or if root, link reference frame is the model, where the model itself in sdf may be offset + // Seems like need to build tree of joints and links starting with root link + + std::vector visited_links_; + std::vector link_stack{sdf_canonical_link}; + while (!link_stack.empty()) { + const sdf::Link * sdf_parent_link = link_stack.back(); + urdf::LinkSharedPtr & urdf_parent_link = urdf_model->links_.at(sdf_parent_link->Name()); + link_stack.pop_back(); + + // Check if there is a kinematic loop + if (visited_links_.end() != std::find(visited_links_.begin(), visited_links_.end(), sdf_parent_link) ) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Not a tree because link [" + sdf_parent_link->Name() + "] was visited twice"); + return nullptr; + } + visited_links_.emplace_back(sdf_parent_link); + + sdf::Errors pose_errors; + + // Look for joints attached to this link + for (uint64_t j = 0; j < sdf_model.JointCount(); ++j) { + const sdf::Joint * sdf_joint = sdf_model.JointByIndex(j); + + if (!sdf_joint) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get sdf joint"); + return nullptr; + } + + if (sdf_joint->ParentLinkName() == sdf_parent_link->Name()) { + urdf::JointSharedPtr & urdf_joint = urdf_model->joints_.at(sdf_joint->Name()); + // Append to child joints + urdf_parent_link->child_joints.push_back(urdf_joint); + + // Set the joint origin to the transform from the joint to the parent link + ignition::math::Pose3d joint_pose; + pose_errors = sdf_joint->SemanticPose().Resolve(joint_pose, sdf_parent_link->Name()); + if (!pose_errors.empty()) { + errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get transfrom from joint [" + sdf_joint->Name() + + "] to link [" + sdf_parent_link->Name() + "]"); + return nullptr; + } + urdf_joint->parent_to_joint_origin_transform = convert_pose(joint_pose); + + // get child link + const std::string & child_link_name = urdf_joint->child_link_name; + const sdf::Link * sdf_child_link = sdf_model.LinkByName(child_link_name); + if (!sdf_child_link) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get child link [" + child_link_name + "]"); + return nullptr; + } + urdf::LinkSharedPtr & urdf_child_link = urdf_model->links_.at(child_link_name); + + // child link is attached to parent joint + urdf_child_link->parent_joint = urdf_joint; + + // parent link has reference to child link + urdf_parent_link->child_links.push_back(urdf_child_link); + + // Explore this child link later + link_stack.push_back(sdf_child_link); + } + } + } + + return urdf_model; +} + +urdf::LinkSharedPtr +sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) +{ + urdf::LinkSharedPtr urdf_link = std::make_shared(); + + urdf_link->name = sdf_link.Name(); + + urdf_link->inertial = std::make_shared(); + if (!urdf_link->inertial) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to create inertial for link [" + sdf_link.Name() + "]"); + return nullptr; + } + urdf_link->inertial->mass = sdf_link.Inertial().MassMatrix().Mass(); + + // TODO(sloretz) inertial pose + // TODO(sloretz) ixx, ixy, ixz, iyy, iyz, izz + + // TODO(sloretz) visual + + // TODO(sloretz) collision + + return urdf_link; +} + +urdf::JointSharedPtr +sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) +{ + urdf::JointSharedPtr urdf_joint = std::make_shared(); + + urdf_joint->name = sdf_joint.Name(); + + switch (sdf_joint.Type()) { + case sdf::JointType::CONTINUOUS: + urdf_joint->type = urdf::Joint::CONTINUOUS; + break; + case sdf::JointType::REVOLUTE: + urdf_joint->type = urdf::Joint::REVOLUTE; + break; + case sdf::JointType::FIXED: + urdf_joint->type = urdf::Joint::FIXED; + break; + case sdf::JointType::PRISMATIC: + urdf_joint->type = urdf::Joint::PRISMATIC; + break; + case sdf::JointType::INVALID: + // fall through + case sdf::JointType::BALL: + // fall through + case sdf::JointType::GEARBOX: + // fall through + case sdf::JointType::REVOLUTE2: + // fall through + case sdf::JointType::SCREW: + // fall through + case sdf::JointType::UNIVERSAL: + // fall through + default: + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Unsupported joint type on joint [" + sdf_joint.Name() + "]"); + return nullptr; + }; + + const sdf::JointAxis * sdf_axis = sdf_joint.Axis(0); + urdf_joint->axis.x = sdf_axis->Xyz().X(); + urdf_joint->axis.y = sdf_axis->Xyz().Y(); + urdf_joint->axis.z = sdf_axis->Xyz().Z(); + + urdf_joint->child_link_name = sdf_joint.ChildLinkName(); + urdf_joint->parent_link_name = sdf_joint.ParentLinkName(); + + return urdf_joint; +} + +urdf::Pose +sdformat_urdf::convert_pose(const ignition::math::Pose3d & sdf_pose) +{ + urdf::Pose pose; + pose.position.x = sdf_pose.Pos().X(); + pose.position.y = sdf_pose.Pos().Y(); + pose.position.z = sdf_pose.Pos().Z(); + + pose.rotation.x = sdf_pose.Rot().X(); + pose.rotation.y = sdf_pose.Rot().Y(); + pose.rotation.z = sdf_pose.Rot().Z(); + pose.rotation.w = sdf_pose.Rot().W(); + + return pose; +} diff --git a/src/sdformat_urdf_plugin.cpp b/src/sdformat_urdf_plugin.cpp new file mode 100644 index 00000000..83499fd5 --- /dev/null +++ b/src/sdformat_urdf_plugin.cpp @@ -0,0 +1,58 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 +#include "sdformat_urdf/sdformat_urdf.hpp" +#include + +namespace sdformat_urdf { + +class SDFormatURDFParser : public urdf::URDFParser +{ +public: + + SDFormatURDFParser() = default; + virtual ~SDFormatURDFParser() = default; + + urdf::ModelInterfaceSharedPtr + parse(const std::string & data) override + { + urdf::ModelInterfaceSharedPtr urdf_cpp; + sdf::Errors errors; + urdf_cpp = sdformat_urdf::parse(data, errors); + + if (urdf_cpp) { + return urdf_cpp; + } + + for (const sdf::Error & error : errors) { + RCUTILS_LOG_ERROR_NAMED("sdformat_urdf", "%s", error.Message().c_str()); + } + if (errors.empty()) { + RCUTILS_LOG_ERROR_NAMED("sdformat_urdf", "Failed to parse but no errors reported"); + } + return nullptr; + } + + size_t + might_handle(const std::string & data) override + { + return data.find(" // NOLINT +PLUGINLIB_EXPORT_CLASS(sdformat_urdf::SDFormatURDFParser, urdf::URDFParser) From 035dbc8bdcdfc42a4dc8caa95bead84b551a3d65 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 17 Jul 2020 08:52:42 -0700 Subject: [PATCH 002/152] Visual and Collision with Box geometry Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 128 +++++++++++++++++++++++++++++++++++++++++- 1 file changed, 126 insertions(+), 2 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 8c1ff976..83b0378a 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -33,6 +33,9 @@ convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors); urdf::Pose convert_pose(const ignition::math::Pose3d & sdf_pose); + +urdf::GeometrySharedPtr +convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors & errors); } // namespace sdformat_urdf urdf::ModelInterfaceSharedPtr @@ -250,9 +253,101 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) // TODO(sloretz) inertial pose // TODO(sloretz) ixx, ixy, ixz, iyy, iyz, izz - // TODO(sloretz) visual + for (uint64_t vi = 0; vi < sdf_link.VisualCount(); ++vi) { + const sdf::Visual * sdf_visual = sdf_link.VisualByIndex(vi); + if (!sdf_visual) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get visual on lilnk [" + sdf_link.Name() + "]"); + return nullptr; + } + + auto urdf_visual = std::make_shared(); + + urdf_visual->name = sdf_visual->Name(); + + // URDF visual is relative to link origin + ignition::math::Pose3d visual_pose; + sdf::Errors pose_errors = sdf_visual->SemanticPose().Resolve(visual_pose, sdf_link.Name()); + if (!pose_errors.empty()) { + errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get transfrom from visual [" + sdf_visual->Name() + + "] to link [" + sdf_link.Name() + "]"); + return nullptr; + } + urdf_visual->origin = convert_pose(visual_pose); + + urdf_visual->geometry = convert_geometry(*sdf_visual->Geom(), errors); + if (!urdf_visual->geometry) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to convert geometry on visual [" + sdf_visual->Name()+ "]"); + return nullptr; + } + + const sdf::Material * sdf_material = sdf_visual->Material(); + if (sdf_material) { + // TODO(sloretz) textures + // TODO(sloretz) error if any file names we can't resolve are given + auto urdf_material = std::make_shared(); + // sdf materials don't have names, so assign it the visual's name and hope that's unique enough + urdf_material->name = sdf_visual->Name(); + // Color support is pretty limited in urdf, just take the ambient (color when no light applied) + urdf_material->color.r = sdf_material->Ambient().R(); + urdf_material->color.g = sdf_material->Ambient().G(); + urdf_material->color.b = sdf_material->Ambient().B(); + urdf_material->color.a = sdf_material->Ambient().A(); + + urdf_visual->material = urdf_material; + } + + if (0u == vi) { + urdf_link->visual = urdf_visual; + } + urdf_link->visual_array.push_back(urdf_visual); + } + + for (uint64_t vi = 0; vi < sdf_link.CollisionCount(); ++vi) { + const sdf::Collision * sdf_collision = sdf_link.CollisionByIndex(vi); + if (!sdf_collision) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get collision on lilnk [" + sdf_link.Name() + "]"); + return nullptr; + } + + auto urdf_collision = std::make_shared(); + + urdf_collision->name = sdf_collision->Name(); - // TODO(sloretz) collision + // URDF collision is relative to link origin + ignition::math::Pose3d collision_pose; + sdf::Errors pose_errors = sdf_collision->SemanticPose().Resolve(collision_pose, sdf_link.Name()); + if (!pose_errors.empty()) { + errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get transfrom from collision [" + sdf_collision->Name() + + "] to link [" + sdf_link.Name() + "]"); + return nullptr; + } + urdf_collision->origin = convert_pose(collision_pose); + + urdf_collision->geometry = convert_geometry(*sdf_collision->Geom(), errors); + if (!urdf_collision->geometry) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to convert geometry on collision [" + sdf_collision->Name()+ "]"); + return nullptr; + } + + if (0u == vi) { + urdf_link->collision = urdf_collision; + } + urdf_link->collision_array.push_back(urdf_collision); + } return urdf_link; } @@ -322,3 +417,32 @@ sdformat_urdf::convert_pose(const ignition::math::Pose3d & sdf_pose) return pose; } + +urdf::GeometrySharedPtr +sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors & errors) +{ + if (sdf_geometry.BoxShape()) { + const sdf::Box * box = sdf_geometry.BoxShape(); + auto urdf_box = std::make_shared(); + urdf_box->dim.x = box->Size().X(); + urdf_box->dim.y = box->Size().Y(); + urdf_box->dim.z = box->Size().Z(); + return urdf_box; + } else if (sdf_geometry.CylinderShape()) { + // TODO + } else if (sdf_geometry.SphereShape()) { + // TODO + } else if (sdf_geometry.PlaneShape()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Plane geometry cannot be converted to urdf C++ structures"); + return nullptr; + } else if (sdf_geometry.MeshShape()) { + // TODO + } + + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Unknown geometry shape"); + return nullptr; +} From c80edcc1bd5e7ff62cdb981feb15f8e67f8cf1f2 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 17 Jul 2020 15:03:51 -0700 Subject: [PATCH 003/152] Sphere geometry Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 83b0378a..d1e29dfb 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -431,7 +431,10 @@ sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors } else if (sdf_geometry.CylinderShape()) { // TODO } else if (sdf_geometry.SphereShape()) { - // TODO + const sdf::Sphere * sphere = sdf_geometry.SphereShape(); + auto urdf_sphere = std::make_shared(); + urdf_sphere->radius = sphere->Radius(); + return urdf_sphere; } else if (sdf_geometry.PlaneShape()) { errors.emplace_back( sdf::ErrorCode::STRING_READ, From 30de8008100e3a2785747c4a33a58feece71f778 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 17 Jul 2020 15:29:06 -0700 Subject: [PATCH 004/152] Cylinder geometry Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index d1e29dfb..49501729 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -429,7 +429,11 @@ sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors urdf_box->dim.z = box->Size().Z(); return urdf_box; } else if (sdf_geometry.CylinderShape()) { - // TODO + const sdf::Cylinder * cylinder = sdf_geometry.CylinderShape(); + auto urdf_cylinder = std::make_shared(); + urdf_cylinder->length = cylinder->Length(); + urdf_cylinder->radius = cylinder->Radius(); + return urdf_cylinder; } else if (sdf_geometry.SphereShape()) { const sdf::Sphere * sphere = sdf_geometry.SphereShape(); auto urdf_sphere = std::make_shared(); From 9f9ac7ea64d16bba876b5d150d0d75ebb9f83b11 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 17 Jul 2020 17:55:36 -0700 Subject: [PATCH 005/152] Mesh support Signed-off-by: Shane Loretz --- CMakeLists.txt | 5 +++++ package.xml | 3 +++ src/sdformat_urdf.cpp | 13 ++++++++++++- 3 files changed, 20 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 808b44e1..7e5eb251 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,6 +14,7 @@ find_package(ament_cmake_ros REQUIRED) find_package(pluginlib REQUIRED) find_package(rcutils REQUIRED) +find_package(resource_retriever REQUIRED) find_package(sdformat9 REQUIRED) find_package(urdfdom_headers REQUIRED) find_package(urdf_parser_plugin REQUIRED) @@ -26,6 +27,10 @@ target_link_libraries(sdformat_urdf PUBLIC sdformat9::sdformat9 ) +target_link_libraries(sdformat_urdf + PRIVATE + resource_retriever::resource_retriever +) target_include_directories(sdformat_urdf PUBLIC "$" diff --git a/package.xml b/package.xml index 32e11304..cee4ac7b 100644 --- a/package.xml +++ b/package.xml @@ -21,9 +21,12 @@ liburdfdom-headers-dev pluginlib + resource_retriever urdf urdf_parser_plugin + resource_retriever + resource_retriever urdf urdf_parser_plugin diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 49501729..1ea8fd02 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include #include @@ -445,7 +446,17 @@ sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors "Plane geometry cannot be converted to urdf C++ structures"); return nullptr; } else if (sdf_geometry.MeshShape()) { - // TODO + const std::string & uri = sdf_geometry.MeshShape()->Uri(); + const std::string local_path = resource_retriever::Retriever().resolve(uri); + if (local_path.empty()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Unable to resolve uri [" + uri + "]"); + } + auto urdf_mesh = std::make_shared(); + urdf_mesh->filename = "file://" + local_path; + // TODO(sloretz) scale + return urdf_mesh; } errors.emplace_back( From 4f0ef012274e6f79d8c38010966a096feb9c26a7 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 3 Aug 2020 14:00:39 -0700 Subject: [PATCH 006/152] remove TODO comment about resolving poses Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 1ea8fd02..da37f7b1 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -154,14 +154,7 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) } } - // Start with root link (sdf canonical frame) and recurse this function: - // - // TODO what about coordinate frames? - // Link pose in URDF is relative to link reference frame - // Link reference frame is parent joint - joint in which this frame is the child link - // Or if root, link reference frame is the model, where the model itself in sdf may be offset - // Seems like need to build tree of joints and links starting with root link - + // Start with root link and resolve the poses one joint at a time depth-first std::vector visited_links_; std::vector link_stack{sdf_canonical_link}; while (!link_stack.empty()) { From db1551b3c4129c8b3abcf13ee76880413e4db108 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 3 Aug 2020 16:23:00 -0700 Subject: [PATCH 007/152] Let downstream worry about resolving mesh URIs Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index da37f7b1..f53f7b57 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -440,14 +440,14 @@ sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors return nullptr; } else if (sdf_geometry.MeshShape()) { const std::string & uri = sdf_geometry.MeshShape()->Uri(); - const std::string local_path = resource_retriever::Retriever().resolve(uri); - if (local_path.empty()) { - errors.emplace_back( - sdf::ErrorCode::STRING_READ, - "Unable to resolve uri [" + uri + "]"); - } - auto urdf_mesh = std::make_shared(); - urdf_mesh->filename = "file://" + local_path; + + // The only example in ROS that I've found using urdf_mesh->filename is + // the RobotModel plugin in RViz. This plugin uses resource retriever to + // resolve the filename - which may be a URI - to the mesh resource. + // Pass it here unmodified, ignoring that SDFormat relative paths may not + // be resolvable this way. + urdf_mesh->filename = uri; + // TODO(sloretz) scale return urdf_mesh; } From c84a46db49923115a56319d0ef0f07a6136b97d1 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 3 Aug 2020 16:37:39 -0700 Subject: [PATCH 008/152] Reword assumption about kinematic root link Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index f53f7b57..b65e0d14 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -108,7 +108,8 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) } } - // sdf canonical link -> urdf root link + // Assume sdf canonical link is urdf root link + // TODO(osrf/sdformat#273) In future use API for getting kinematic root link const sdf::Link * sdf_canonical_link = sdf_model.CanonicalLink(); if (!sdf_canonical_link) { errors.emplace_back( From ecb6e32e8ede94cf00ac7051510312acc1f33af5 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 3 Aug 2020 16:41:58 -0700 Subject: [PATCH 009/152] Make fall through comments easier to see Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 18 ++++++------------ 1 file changed, 6 insertions(+), 12 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index b65e0d14..0d1c60a4 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -367,18 +367,12 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) case sdf::JointType::PRISMATIC: urdf_joint->type = urdf::Joint::PRISMATIC; break; - case sdf::JointType::INVALID: - // fall through - case sdf::JointType::BALL: - // fall through - case sdf::JointType::GEARBOX: - // fall through - case sdf::JointType::REVOLUTE2: - // fall through - case sdf::JointType::SCREW: - // fall through - case sdf::JointType::UNIVERSAL: - // fall through + case sdf::JointType::INVALID: // Unsupported: fall through to default + case sdf::JointType::BALL: // | + case sdf::JointType::GEARBOX: // | + case sdf::JointType::REVOLUTE2: // | + case sdf::JointType::SCREW: // | + case sdf::JointType::UNIVERSAL: // V default: errors.emplace_back( sdf::ErrorCode::STRING_READ, From dd02e31d2eee03bb95b3e28d7e5374a55a9a3915 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 3 Aug 2020 17:27:47 -0700 Subject: [PATCH 010/152] Create urdf_mesh variable Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 0d1c60a4..301f2d76 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -435,7 +435,7 @@ sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors return nullptr; } else if (sdf_geometry.MeshShape()) { const std::string & uri = sdf_geometry.MeshShape()->Uri(); - + auto urdf_mesh = std::make_shared(); // The only example in ROS that I've found using urdf_mesh->filename is // the RobotModel plugin in RViz. This plugin uses resource retriever to // resolve the filename - which may be a URI - to the mesh resource. From 59677567277aff6bb786c4d5fd46173fec8a96ff Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 3 Aug 2020 17:37:26 -0700 Subject: [PATCH 011/152] Handle inertia Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 301f2d76..57e7fb94 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -236,6 +236,7 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) urdf_link->name = sdf_link.Name(); + const ignition::math::Inertiald sdf_inertia = sdf_link.Inertial(); urdf_link->inertial = std::make_shared(); if (!urdf_link->inertial) { errors.emplace_back( @@ -243,10 +244,15 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) "Failed to create inertial for link [" + sdf_link.Name() + "]"); return nullptr; } - urdf_link->inertial->mass = sdf_link.Inertial().MassMatrix().Mass(); - - // TODO(sloretz) inertial pose - // TODO(sloretz) ixx, ixy, ixz, iyy, iyz, izz + urdf_link->inertial->mass = sdf_inertia.MassMatrix().Mass(); + // Inertial Pose is relative to link origin + urdf_link->inertial->origin = convert_pose(sdf_inertia.Pose()); + urdf_link->inertial->ixx = sdf_inertia.MassMatrix().Ixx(); + urdf_link->inertial->ixy = sdf_inertia.MassMatrix().Ixy(); + urdf_link->inertial->ixz = sdf_inertia.MassMatrix().Ixz(); + urdf_link->inertial->iyy = sdf_inertia.MassMatrix().Iyy(); + urdf_link->inertial->iyz = sdf_inertia.MassMatrix().Iyz(); + urdf_link->inertial->izz = sdf_inertia.MassMatrix().Izz(); for (uint64_t vi = 0; vi < sdf_link.VisualCount(); ++vi) { const sdf::Visual * sdf_visual = sdf_link.VisualByIndex(vi); From edf7519b6b0ab92d765952f861f26fd8436d8553 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 4 Aug 2020 11:00:11 -0700 Subject: [PATCH 012/152] Mesh scale Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 57e7fb94..6d5d1e97 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -449,7 +449,9 @@ sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors // be resolvable this way. urdf_mesh->filename = uri; - // TODO(sloretz) scale + urdf_mesh->scale.x = sdf_geometry.MeshShape()->Scale().X(); + urdf_mesh->scale.y = sdf_geometry.MeshShape()->Scale().Y(); + urdf_mesh->scale.z = sdf_geometry.MeshShape()->Scale().Z(); return urdf_mesh; } From 3c0a28fdc8e04c3db860fd1b324528f991ee4273 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 4 Aug 2020 11:07:09 -0700 Subject: [PATCH 013/152] Visibility control header Signed-off-by: Shane Loretz --- include/sdformat_urdf/sdformat_urdf.hpp | 5 ++ include/sdformat_urdf/visibility_control.hpp | 58 ++++++++++++++++++++ 2 files changed, 63 insertions(+) create mode 100644 include/sdformat_urdf/visibility_control.hpp diff --git a/include/sdformat_urdf/sdformat_urdf.hpp b/include/sdformat_urdf/sdformat_urdf.hpp index e434bc02..88edded2 100644 --- a/include/sdformat_urdf/sdformat_urdf.hpp +++ b/include/sdformat_urdf/sdformat_urdf.hpp @@ -18,16 +18,21 @@ #include #include +#include + namespace sdformat_urdf { /// \brief Parse an SDFormat XML string and return URDF C++ structures +SDFORMAT_URDF_PUBLIC urdf::ModelInterfaceSharedPtr parse(const std::string & data, sdf::Errors & errors); /// \brief Convert SDFormat C++ structures to URDF C++ structures +SDFORMAT_URDF_PUBLIC urdf::ModelInterfaceSharedPtr sdf_to_urdf(const sdf::Root & sdf_dom, sdf::Errors & errors); /// \brief Convert SDFormat Model to URDF Model +SDFORMAT_URDF_PUBLIC urdf::ModelInterfaceSharedPtr convert_model(const sdf::Model & sdf_model, sdf::Errors & errors); } // namespace sdformat_urdf diff --git a/include/sdformat_urdf/visibility_control.hpp b/include/sdformat_urdf/visibility_control.hpp new file mode 100644 index 00000000..a36f1c38 --- /dev/null +++ b/include/sdformat_urdf/visibility_control.hpp @@ -0,0 +1,58 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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. + +#ifndef SDFORMAT_URDF__VISIBILITY_CONTROL_H_ +#define SDFORMAT_URDF__VISIBILITY_CONTROL_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define SDFORMAT_URDF_EXPORT __attribute__ ((dllexport)) + #define SDFORMAT_URDF_IMPORT __attribute__ ((dllimport)) + #else + #define SDFORMAT_URDF_EXPORT __declspec(dllexport) + #define SDFORMAT_URDF_IMPORT __declspec(dllimport) + #endif + #ifdef SDFORMAT_URDF_BUILDING_DLL + #define SDFORMAT_URDF_PUBLIC SDFORMAT_URDF_EXPORT + #else + #define SDFORMAT_URDF_PUBLIC SDFORMAT_URDF_IMPORT + #endif + #define SDFORMAT_URDF_PUBLIC_TYPE SDFORMAT_URDF_PUBLIC + #define SDFORMAT_URDF_LOCAL +#else + #define SDFORMAT_URDF_EXPORT __attribute__ ((visibility("default"))) + #define SDFORMAT_URDF_IMPORT + #if __GNUC__ >= 4 + #define SDFORMAT_URDF_PUBLIC __attribute__ ((visibility("default"))) + #define SDFORMAT_URDF_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define SDFORMAT_URDF_PUBLIC + #define SDFORMAT_URDF_LOCAL + #endif + #define SDFORMAT_URDF_PUBLIC_TYPE +#endif + +#ifdef __cplusplus +} +#endif + +#endif // SDFORMAT_URDF__VISIBILITY_CONTROL_H_ From d6021c64455a229f83a99206eea0eb41eb43b9e9 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 13 Aug 2020 09:25:19 -0700 Subject: [PATCH 014/152] Remove resource_retriever dependency Signed-off-by: Shane Loretz --- CMakeLists.txt | 5 ----- package.xml | 3 --- src/sdformat_urdf.cpp | 1 - 3 files changed, 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7e5eb251..808b44e1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,6 @@ find_package(ament_cmake_ros REQUIRED) find_package(pluginlib REQUIRED) find_package(rcutils REQUIRED) -find_package(resource_retriever REQUIRED) find_package(sdformat9 REQUIRED) find_package(urdfdom_headers REQUIRED) find_package(urdf_parser_plugin REQUIRED) @@ -27,10 +26,6 @@ target_link_libraries(sdformat_urdf PUBLIC sdformat9::sdformat9 ) -target_link_libraries(sdformat_urdf - PRIVATE - resource_retriever::resource_retriever -) target_include_directories(sdformat_urdf PUBLIC "$" diff --git a/package.xml b/package.xml index cee4ac7b..32e11304 100644 --- a/package.xml +++ b/package.xml @@ -21,12 +21,9 @@ liburdfdom-headers-dev pluginlib - resource_retriever urdf urdf_parser_plugin - resource_retriever - resource_retriever urdf urdf_parser_plugin diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 6d5d1e97..1cc77263 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -18,7 +18,6 @@ #include #include -#include #include #include #include From 348723bfc5230be0d33dbebbecdbde00baa0e120 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 13 Aug 2020 09:25:39 -0700 Subject: [PATCH 015/152] Support joint axis expressed in other frames Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 30 ++++++++++++++++++++++++++---- 1 file changed, 26 insertions(+), 4 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 1cc77263..477de7e5 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -359,18 +359,24 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) urdf_joint->name = sdf_joint.Name(); + size_t num_axes = 0; + switch (sdf_joint.Type()) { case sdf::JointType::CONTINUOUS: urdf_joint->type = urdf::Joint::CONTINUOUS; + num_axes = 1; break; case sdf::JointType::REVOLUTE: urdf_joint->type = urdf::Joint::REVOLUTE; + num_axes = 1; break; case sdf::JointType::FIXED: urdf_joint->type = urdf::Joint::FIXED; + num_axes = 0; break; case sdf::JointType::PRISMATIC: urdf_joint->type = urdf::Joint::PRISMATIC; + num_axes = 1; break; case sdf::JointType::INVALID: // Unsupported: fall through to default case sdf::JointType::BALL: // | @@ -385,10 +391,26 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) return nullptr; }; - const sdf::JointAxis * sdf_axis = sdf_joint.Axis(0); - urdf_joint->axis.x = sdf_axis->Xyz().X(); - urdf_joint->axis.y = sdf_axis->Xyz().Y(); - urdf_joint->axis.z = sdf_axis->Xyz().Z(); + // Supported joints have at most one axis + if (1 == num_axes) { + const sdf::JointAxis * sdf_axis = sdf_joint.Axis(0); + + // URDF expects axis to be expressed in the joint frame + ignition::math::Vector3d axis_xyz; + sdf::Errors axis_errors = sdf_axis->ResolveXyz(axis_xyz, sdf_joint.Name()); + if (!axis_errors.empty()) { + errors.insert(errors.end(), axis_errors.begin(), axis_errors.end()); + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get transfrom of joint axis in frame [" + sdf_axis->XyzExpressedIn() + + "] to joint [" + sdf_joint.Name() + "]"); + return nullptr; + } + + urdf_joint->axis.x = axis_xyz.X(); + urdf_joint->axis.y = axis_xyz.Y(); + urdf_joint->axis.z = axis_xyz.Z(); + } urdf_joint->child_link_name = sdf_joint.ChildLinkName(); urdf_joint->parent_link_name = sdf_joint.ParentLinkName(); From ab6637bcb03d00f08facd94da7956ffe25cb6bf4 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 21 Sep 2020 14:11:41 -0700 Subject: [PATCH 016/152] Include ignition/math/Pose3.hh Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 477de7e5..e8aaf275 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include #include From 21adf189d3d02e72014e5a642a15123c7ca5cf32 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 21 Sep 2020 16:04:18 -0700 Subject: [PATCH 017/152] Use final on plugin class Signed-off-by: Shane Loretz --- src/sdformat_urdf_plugin.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/sdformat_urdf_plugin.cpp b/src/sdformat_urdf_plugin.cpp index 83499fd5..1ab21350 100644 --- a/src/sdformat_urdf_plugin.cpp +++ b/src/sdformat_urdf_plugin.cpp @@ -19,12 +19,12 @@ namespace sdformat_urdf { -class SDFormatURDFParser : public urdf::URDFParser +class SDFormatURDFParser final : public urdf::URDFParser { public: SDFormatURDFParser() = default; - virtual ~SDFormatURDFParser() = default; + ~SDFormatURDFParser() = default; urdf::ModelInterfaceSharedPtr parse(const std::string & data) override From 7a5ad72442456120647b863d9522085c4c5284ff Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 21 Sep 2020 16:16:47 -0700 Subject: [PATCH 018/152] Use TinyXML2 to filter non-sdf XML documents Signed-off-by: Shane Loretz --- CMakeLists.txt | 3 +++ package.xml | 2 ++ src/sdformat_urdf_plugin.cpp | 17 +++++++++++++++++ 3 files changed, 22 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 808b44e1..77685426 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -17,6 +17,8 @@ find_package(rcutils REQUIRED) find_package(sdformat9 REQUIRED) find_package(urdfdom_headers REQUIRED) find_package(urdf_parser_plugin REQUIRED) +find_package(tinyxml2_vendor REQUIRED) +find_package(TinyXML2 REQUIRED) # Add sdformat_urdf shared library add_library(sdformat_urdf SHARED @@ -43,6 +45,7 @@ target_link_libraries(sdformat_urdf_plugin PUBLIC ament_target_dependencies(sdformat_urdf_plugin PUBLIC "pluginlib" "rcutils" + "TinyXML2" "urdf_parser_plugin" ) diff --git a/package.xml b/package.xml index 32e11304..efcb098d 100644 --- a/package.xml +++ b/package.xml @@ -21,9 +21,11 @@ liburdfdom-headers-dev pluginlib + tinyxml2_vendor urdf urdf_parser_plugin + tinyxml2_vendor urdf urdf_parser_plugin diff --git a/src/sdformat_urdf_plugin.cpp b/src/sdformat_urdf_plugin.cpp index 1ab21350..726dfa09 100644 --- a/src/sdformat_urdf_plugin.cpp +++ b/src/sdformat_urdf_plugin.cpp @@ -12,9 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include "sdformat_urdf/sdformat_urdf.hpp" +#include #include namespace sdformat_urdf { @@ -49,6 +51,21 @@ class SDFormatURDFParser final : public urdf::URDFParser size_t might_handle(const std::string & data) override { + tinyxml2::XMLDocument doc; + const tinyxml2::XMLError error = doc.Parse(data.c_str()); + if (error == tinyxml2::XML_SUCCESS) { + // Since it's an XML document it must have `` as the first tag + const tinyxml2::XMLElement * root = doc.RootElement(); + if (std::string("sdf") != root->Name()) { + std::cout << "'" << root->Name() << "'\n"; + return std::numeric_limits::max(); + } + } + + // Possiblities: + // 1) It is not an XML based robot description + // 2) It is an XML based robot description, but there's an XML syntax error + // 3) It is an SDFormat XML with correct XML syntax return data.find(" Date: Mon, 21 Sep 2020 16:51:27 -0700 Subject: [PATCH 019/152] Apache 2.0 License Signed-off-by: Shane Loretz --- CONTRIBUTING.md | 18 +++++ LICENSE | 203 ++++++++++++++++++++++++++++++++++++++++++++++-- 2 files changed, 215 insertions(+), 6 deletions(-) create mode 100644 CONTRIBUTING.md diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 00000000..cfba094d --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,18 @@ +Any contribution that you make to this repository will +be under the Apache 2 License, as dictated by that +[license](http://www.apache.org/licenses/LICENSE-2.0.html): + +~~~ +5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. +~~~ + +Contributors must sign-off each commit by adding a `Signed-off-by: ...` +line to commit messages to certify that they have the right to submit +the code they are contributing to the project according to the +[Developer Certificate of Origin (DCO)](https://developercertificate.org/). diff --git a/LICENSE b/LICENSE index 3268e9fb..d6456956 100644 --- a/LICENSE +++ b/LICENSE @@ -1,11 +1,202 @@ -Copyright 2013-2020 Willow Garage, Inc. -Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ -1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION -2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + 1. Definitions. -3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. From 63fd805fb43c06f63253734068a6b258e95dd99a Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 21 Sep 2020 17:02:57 -0700 Subject: [PATCH 020/152] Satisfy uncrustify Signed-off-by: Shane Loretz --- include/sdformat_urdf/sdformat_urdf.hpp | 3 ++- src/sdformat_urdf.cpp | 32 ++++++++++++++----------- src/sdformat_urdf_plugin.cpp | 5 ++-- 3 files changed, 22 insertions(+), 18 deletions(-) diff --git a/include/sdformat_urdf/sdformat_urdf.hpp b/include/sdformat_urdf/sdformat_urdf.hpp index 88edded2..bdf87ac6 100644 --- a/include/sdformat_urdf/sdformat_urdf.hpp +++ b/include/sdformat_urdf/sdformat_urdf.hpp @@ -20,7 +20,8 @@ #include -namespace sdformat_urdf { +namespace sdformat_urdf +{ /// \brief Parse an SDFormat XML string and return URDF C++ structures SDFORMAT_URDF_PUBLIC urdf::ModelInterfaceSharedPtr diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index e8aaf275..867a71ed 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -23,7 +23,8 @@ #include #include -namespace sdformat_urdf { +namespace sdformat_urdf +{ /// \brief Convert SDFormat Link to URDF Link urdf::LinkSharedPtr convert_link(const sdf::Link & sdf_link, sdf::Errors & errors); @@ -164,7 +165,9 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) link_stack.pop_back(); // Check if there is a kinematic loop - if (visited_links_.end() != std::find(visited_links_.begin(), visited_links_.end(), sdf_parent_link) ) { + if (visited_links_.end() != + std::find(visited_links_.begin(), visited_links_.end(), sdf_parent_link)) + { errors.emplace_back( sdf::ErrorCode::STRING_READ, "Not a tree because link [" + sdf_parent_link->Name() + "] was visited twice"); @@ -197,8 +200,8 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get transfrom from joint [" + sdf_joint->Name() - + "] to link [" + sdf_parent_link->Name() + "]"); + "Failed to get transfrom from joint [" + sdf_joint->Name() + + "] to link [" + sdf_parent_link->Name() + "]"); return nullptr; } urdf_joint->parent_to_joint_origin_transform = convert_pose(joint_pose); @@ -274,8 +277,8 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get transfrom from visual [" + sdf_visual->Name() - + "] to link [" + sdf_link.Name() + "]"); + "Failed to get transfrom from visual [" + sdf_visual->Name() + + "] to link [" + sdf_link.Name() + "]"); return nullptr; } urdf_visual->origin = convert_pose(visual_pose); @@ -284,7 +287,7 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) if (!urdf_visual->geometry) { errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to convert geometry on visual [" + sdf_visual->Name()+ "]"); + "Failed to convert geometry on visual [" + sdf_visual->Name() + "]"); return nullptr; } @@ -325,13 +328,14 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) // URDF collision is relative to link origin ignition::math::Pose3d collision_pose; - sdf::Errors pose_errors = sdf_collision->SemanticPose().Resolve(collision_pose, sdf_link.Name()); + sdf::Errors pose_errors = + sdf_collision->SemanticPose().Resolve(collision_pose, sdf_link.Name()); if (!pose_errors.empty()) { errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get transfrom from collision [" + sdf_collision->Name() - + "] to link [" + sdf_link.Name() + "]"); + "Failed to get transfrom from collision [" + sdf_collision->Name() + + "] to link [" + sdf_link.Name() + "]"); return nullptr; } urdf_collision->origin = convert_pose(collision_pose); @@ -340,7 +344,7 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) if (!urdf_collision->geometry) { errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to convert geometry on collision [" + sdf_collision->Name()+ "]"); + "Failed to convert geometry on collision [" + sdf_collision->Name() + "]"); return nullptr; } @@ -390,7 +394,7 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) sdf::ErrorCode::STRING_READ, "Unsupported joint type on joint [" + sdf_joint.Name() + "]"); return nullptr; - }; + } // Supported joints have at most one axis if (1 == num_axes) { @@ -403,8 +407,8 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) errors.insert(errors.end(), axis_errors.begin(), axis_errors.end()); errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get transfrom of joint axis in frame [" + sdf_axis->XyzExpressedIn() - + "] to joint [" + sdf_joint.Name() + "]"); + "Failed to get transfrom of joint axis in frame [" + sdf_axis->XyzExpressedIn() + + "] to joint [" + sdf_joint.Name() + "]"); return nullptr; } diff --git a/src/sdformat_urdf_plugin.cpp b/src/sdformat_urdf_plugin.cpp index 726dfa09..a0c68182 100644 --- a/src/sdformat_urdf_plugin.cpp +++ b/src/sdformat_urdf_plugin.cpp @@ -19,12 +19,11 @@ #include #include -namespace sdformat_urdf { - +namespace sdformat_urdf +{ class SDFormatURDFParser final : public urdf::URDFParser { public: - SDFormatURDFParser() = default; ~SDFormatURDFParser() = default; From 16c133f6a19cd29916e32c03cee6c3d37d15f5f9 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 21 Sep 2020 17:13:35 -0700 Subject: [PATCH 021/152] Satisfy cpplint Signed-off-by: Shane Loretz --- include/sdformat_urdf/sdformat_urdf.hpp | 9 +++++++-- include/sdformat_urdf/visibility_control.hpp | 6 +++--- src/sdformat_urdf.cpp | 15 ++++++++------- src/sdformat_urdf_plugin.cpp | 8 +++++--- 4 files changed, 23 insertions(+), 15 deletions(-) diff --git a/include/sdformat_urdf/sdformat_urdf.hpp b/include/sdformat_urdf/sdformat_urdf.hpp index bdf87ac6..9199e546 100644 --- a/include/sdformat_urdf/sdformat_urdf.hpp +++ b/include/sdformat_urdf/sdformat_urdf.hpp @@ -12,13 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#ifndef SDFORMAT_URDF__SDFORMAT_URDF_HPP_ +#define SDFORMAT_URDF__SDFORMAT_URDF_HPP_ #include #include #include -#include +#include + +#include "sdformat_urdf/visibility_control.hpp" namespace sdformat_urdf { @@ -37,3 +40,5 @@ SDFORMAT_URDF_PUBLIC urdf::ModelInterfaceSharedPtr convert_model(const sdf::Model & sdf_model, sdf::Errors & errors); } // namespace sdformat_urdf + +#endif // SDFORMAT_URDF__SDFORMAT_URDF_HPP_ diff --git a/include/sdformat_urdf/visibility_control.hpp b/include/sdformat_urdf/visibility_control.hpp index a36f1c38..acd495f4 100644 --- a/include/sdformat_urdf/visibility_control.hpp +++ b/include/sdformat_urdf/visibility_control.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SDFORMAT_URDF__VISIBILITY_CONTROL_H_ -#define SDFORMAT_URDF__VISIBILITY_CONTROL_H_ +#ifndef SDFORMAT_URDF__VISIBILITY_CONTROL_HPP_ +#define SDFORMAT_URDF__VISIBILITY_CONTROL_HPP_ #ifdef __cplusplus extern "C" @@ -55,4 +55,4 @@ extern "C" } #endif -#endif // SDFORMAT_URDF__VISIBILITY_CONTROL_H_ +#endif // SDFORMAT_URDF__VISIBILITY_CONTROL_HPP_ diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 867a71ed..aca8479f 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -12,16 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "sdformat_urdf/sdformat_urdf.hpp" +#include +#include +#include +#include #include +#include #include #include -#include -#include -#include -#include +#include "sdformat_urdf/sdformat_urdf.hpp" namespace sdformat_urdf { @@ -296,9 +297,9 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) // TODO(sloretz) textures // TODO(sloretz) error if any file names we can't resolve are given auto urdf_material = std::make_shared(); - // sdf materials don't have names, so assign it the visual's name and hope that's unique enough + // sdf materials don't have names, so assign it the visual's name and hope that's unique urdf_material->name = sdf_visual->Name(); - // Color support is pretty limited in urdf, just take the ambient (color when no light applied) + // Color support is pretty limited in urdf, just take the ambient (color with no light) urdf_material->color.r = sdf_material->Ambient().R(); urdf_material->color.g = sdf_material->Ambient().G(); urdf_material->color.b = sdf_material->Ambient().B(); diff --git a/src/sdformat_urdf_plugin.cpp b/src/sdformat_urdf_plugin.cpp index a0c68182..c49d5d22 100644 --- a/src/sdformat_urdf_plugin.cpp +++ b/src/sdformat_urdf_plugin.cpp @@ -12,13 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include - #include -#include "sdformat_urdf/sdformat_urdf.hpp" #include #include +#include +#include + +#include "sdformat_urdf/sdformat_urdf.hpp" + namespace sdformat_urdf { class SDFormatURDFParser final : public urdf::URDFParser From 54c2983b310142b0161e3cac0358605e63b61281 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 21 Sep 2020 17:13:51 -0700 Subject: [PATCH 022/152] Add linter tests Signed-off-by: Shane Loretz --- CMakeLists.txt | 5 +++++ package.xml | 3 +++ 2 files changed, 8 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 77685426..91e65b32 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -68,4 +68,9 @@ ament_export_targets(sdformat_urdf-export) pluginlib_export_plugin_description_file(urdf_parser_plugin "sdformat_urdf_plugin.xml") +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_package() diff --git a/package.xml b/package.xml index efcb098d..5ed51022 100644 --- a/package.xml +++ b/package.xml @@ -29,6 +29,9 @@ urdf urdf_parser_plugin + ament_lint_auto + ament_lint_common + ament_cmake From 1e36db13c37e1db75103dba1bb64d22ae3e14600 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 24 Sep 2020 10:48:11 -0700 Subject: [PATCH 023/152] Add test for pose_link case Signed-off-by: Shane Loretz --- CMakeLists.txt | 9 +++++++++ package.xml | 2 ++ 2 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 91e65b32..200febed 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -70,7 +70,16 @@ pluginlib_export_plugin_description_file(urdf_parser_plugin "sdformat_urdf_plugi if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) + find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + + sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") + configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) + + ament_add_gtest(sdf_pose_tests "test/sdf_pose_tests.cpp") + target_link_libraries(sdf_pose_tests sdformat_urdf) + target_include_directories(sdf_pose_tests PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + endif() ament_package() diff --git a/package.xml b/package.xml index 5ed51022..cf2eb394 100644 --- a/package.xml +++ b/package.xml @@ -29,8 +29,10 @@ urdf urdf_parser_plugin + ament_cmake_gtest ament_lint_auto ament_lint_common + sdformat_test_files ament_cmake From b07df1907774afdad876ac8a008286d9d2163d7e Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 24 Sep 2020 10:48:54 -0700 Subject: [PATCH 024/152] Actually add test files Signed-off-by: Shane Loretz --- test/sdf_paths.hpp.in | 34 ++++++++++++++++++++++++++++++++++ test/sdf_pose_tests.cpp | 38 ++++++++++++++++++++++++++++++++++++++ 2 files changed, 72 insertions(+) create mode 100644 test/sdf_paths.hpp.in create mode 100644 test/sdf_pose_tests.cpp diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in new file mode 100644 index 00000000..2d598df7 --- /dev/null +++ b/test/sdf_paths.hpp.in @@ -0,0 +1,34 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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. + +#ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ + +#define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" + +#include +#include +#include + +inline +std::string +get_file(const char * path) +{ + std::ifstream file_reader(path, std::ifstream::in); + std::stringstream buffer; + buffer << file_reader.rdbuf(); + return buffer.str(); +} + +#endif // SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp new file mode 100644 index 00000000..98d0328b --- /dev/null +++ b/test/sdf_pose_tests.cpp @@ -0,0 +1,38 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 +#include +#include +#include +#include + +#include "sdf_paths.hpp" + + +TEST(Pose, pose_link) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_LINK_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()); + ASSERT_TRUE(model); + + EXPECT_EQ(1u, model->links_.size()); + EXPECT_EQ(0u, model->joints_.size()); + EXPECT_EQ(0u, model->materials_.size()); + EXPECT_EQ("pose_link", model->getName()); + EXPECT_EQ(model->getRoot(), model->getLink("pose_link_link")); +} From 61e4cfe54635d8d16c55e951fbfa574f078df859 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 24 Sep 2020 14:37:36 -0700 Subject: [PATCH 025/152] Add SDF link pose to URDF link members Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 23 +++++++++++++++++++---- 1 file changed, 19 insertions(+), 4 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index aca8479f..597cb4fe 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -240,6 +240,19 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) urdf_link->name = sdf_link.Name(); + // Link pose is by default relative to the model + ignition::math::Pose3d link_pose; + { + sdf::Errors pose_errors = sdf_link.SemanticPose().Resolve(link_pose); + if (!pose_errors.empty()) { + errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Failed to get transform of link [" + sdf_link.Name() + "]"); + return nullptr; + } + } + const ignition::math::Inertiald sdf_inertia = sdf_link.Inertial(); urdf_link->inertial = std::make_shared(); if (!urdf_link->inertial) { @@ -249,8 +262,8 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) return nullptr; } urdf_link->inertial->mass = sdf_inertia.MassMatrix().Mass(); - // Inertial Pose is relative to link origin - urdf_link->inertial->origin = convert_pose(sdf_inertia.Pose()); + // URDF doesn't have link pose concept, so add SDF link pose to inertial + urdf_link->inertial->origin = convert_pose(link_pose + sdf_inertia.Pose()); urdf_link->inertial->ixx = sdf_inertia.MassMatrix().Ixx(); urdf_link->inertial->ixy = sdf_inertia.MassMatrix().Ixy(); urdf_link->inertial->ixz = sdf_inertia.MassMatrix().Ixz(); @@ -282,7 +295,8 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) "] to link [" + sdf_link.Name() + "]"); return nullptr; } - urdf_visual->origin = convert_pose(visual_pose); + // URDF doesn't have link pose concept, so add SDF link pose to visual + urdf_visual->origin = convert_pose(link_pose + visual_pose); urdf_visual->geometry = convert_geometry(*sdf_visual->Geom(), errors); if (!urdf_visual->geometry) { @@ -339,7 +353,8 @@ sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) "] to link [" + sdf_link.Name() + "]"); return nullptr; } - urdf_collision->origin = convert_pose(collision_pose); + // URDF doesn't have link pose concept, so add SDF link pose to collision + urdf_collision->origin = convert_pose(link_pose + collision_pose); urdf_collision->geometry = convert_geometry(*sdf_collision->Geom(), errors); if (!urdf_collision->geometry) { From 2f5f7df101af43af5dbcf3481f5d6647b8ae218f Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 24 Sep 2020 14:38:07 -0700 Subject: [PATCH 026/152] Pose link test actually checks pose Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 35 ++++++++++++++++++++++++++++------- 1 file changed, 28 insertions(+), 7 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 98d0328b..c130aac4 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -14,14 +14,28 @@ #include -#include -#include +#include #include #include +#include +#include #include "sdf_paths.hpp" +#define EXPECT_POSE(expected_ign, actual_urdf) \ + do { \ + const auto actual_ign = ignition::math::Pose3d{ \ + actual_urdf.position.x, \ + actual_urdf.position.y, \ + actual_urdf.position.z, \ + actual_urdf.rotation.w, \ + actual_urdf.rotation.x, \ + actual_urdf.rotation.y, \ + actual_urdf.rotation.z}; \ + EXPECT_EQ(expected_ign, actual_ign); \ + } while (false) + TEST(Pose, pose_link) { sdf::Errors errors; @@ -29,10 +43,17 @@ TEST(Pose, pose_link) get_file(POSE_LINK_PATH_TO_SDF), errors); EXPECT_TRUE(errors.empty()); ASSERT_TRUE(model); - - EXPECT_EQ(1u, model->links_.size()); - EXPECT_EQ(0u, model->joints_.size()); - EXPECT_EQ(0u, model->materials_.size()); EXPECT_EQ("pose_link", model->getName()); - EXPECT_EQ(model->getRoot(), model->getLink("pose_link_link")); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + // URDF link C++ structure does not have an origin - instead the pose of the + // link should be added to the visual, collision, and inertial members. + const ignition::math::Pose3d expected_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + + EXPECT_POSE(expected_pose, link->inertial->origin); + EXPECT_POSE(expected_pose, link->visual->origin); + EXPECT_POSE(expected_pose, link->collision->origin); } From 0c434fd11cd565dd9d5e1c6567d1db99f15ca9fa Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 24 Sep 2020 15:03:25 -0700 Subject: [PATCH 027/152] Add SDF visual pose test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 21 +++++++++++++++++++++ 3 files changed, 23 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 200febed..83556a24 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -74,6 +74,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") + sdformat_test_files_get_model_sdf("pose_visual_path_to_sdf" "pose_visual") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) ament_add_gtest(sdf_pose_tests "test/sdf_pose_tests.cpp") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 2d598df7..2c0dc534 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -16,6 +16,7 @@ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" +#define POSE_VISUAL_PATH_TO_SDF "@pose_visual_path_to_sdf@" #include #include diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index c130aac4..6f751cbd 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -57,3 +57,24 @@ TEST(Pose, pose_link) EXPECT_POSE(expected_pose, link->visual->origin); EXPECT_POSE(expected_pose, link->collision->origin); } + +TEST(Pose, pose_visual) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_VISUAL_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()); + ASSERT_TRUE(model); + EXPECT_EQ("pose_visual", model->getName()); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + const ignition::math::Pose3d expected_visual_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d expected_other_pose(0, 0, 0, 0, 0, 0); + + EXPECT_POSE(expected_other_pose, link->inertial->origin); + EXPECT_POSE(expected_visual_pose, link->visual->origin); + EXPECT_POSE(expected_other_pose, link->collision->origin); +} From 34f3a8e662beede9685d8cab22ccc24e21eb71c9 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 24 Sep 2020 15:10:08 -0700 Subject: [PATCH 028/152] Add SDF collision pose test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 21 +++++++++++++++++++++ 3 files changed, 23 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 83556a24..a16c5a74 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") sdformat_test_files_get_model_sdf("pose_visual_path_to_sdf" "pose_visual") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 2c0dc534..a890d1a4 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,6 +15,7 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" #define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" #define POSE_VISUAL_PATH_TO_SDF "@pose_visual_path_to_sdf@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 6f751cbd..d52d13dd 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -36,6 +36,27 @@ EXPECT_EQ(expected_ign, actual_ign); \ } while (false) +TEST(Pose, pose_collision) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_COLLISION_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()); + ASSERT_TRUE(model); + EXPECT_EQ("pose_collision", model->getName()); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + const ignition::math::Pose3d expected_collision_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d expected_other_pose(0, 0, 0, 0, 0, 0); + + EXPECT_POSE(expected_other_pose, link->inertial->origin); + EXPECT_POSE(expected_other_pose, link->visual->origin); + EXPECT_POSE(expected_collision_pose, link->collision->origin); +} + TEST(Pose, pose_link) { sdf::Errors errors; From 16613893caae58cefbd32469f1526143ce820462 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 24 Sep 2020 15:17:36 -0700 Subject: [PATCH 029/152] Add SDF inertial pose test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 21 +++++++++++++++++++++ 3 files changed, 23 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index a16c5a74..41a04027 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -74,6 +74,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") + sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") sdformat_test_files_get_model_sdf("pose_visual_path_to_sdf" "pose_visual") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index a890d1a4..7205c8cb 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -16,6 +16,7 @@ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" +#define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" #define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" #define POSE_VISUAL_PATH_TO_SDF "@pose_visual_path_to_sdf@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index d52d13dd..6415ed12 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -57,6 +57,27 @@ TEST(Pose, pose_collision) EXPECT_POSE(expected_collision_pose, link->collision->origin); } +TEST(Pose, pose_inertial) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_INERTIAL_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()); + ASSERT_TRUE(model); + EXPECT_EQ("pose_inertial", model->getName()); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + const ignition::math::Pose3d expected_inertial_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d expected_other_pose(0, 0, 0, 0, 0, 0); + + EXPECT_POSE(expected_inertial_pose, link->inertial->origin); + EXPECT_POSE(expected_other_pose, link->visual->origin); + EXPECT_POSE(expected_other_pose, link->collision->origin); +} + TEST(Pose, pose_link) { sdf::Errors errors; From b6ee85ac7d35f716cebc8688e982ea3b66df79ba Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 24 Sep 2020 16:53:26 -0700 Subject: [PATCH 030/152] Add test for model with pose, plus refactor test tools Signed-off-by: Shane Loretz --- CMakeLists.txt | 5 +++- src/sdformat_urdf.cpp | 8 ++++++ test/include/test_tools.hpp | 56 +++++++++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 15 +--------- test/sdf_pose_tests.cpp | 32 ++++++++++----------- 5 files changed, 83 insertions(+), 33 deletions(-) create mode 100644 test/include/test_tools.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 41a04027..a54b3090 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -76,12 +76,15 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") + sdformat_test_files_get_model_sdf("pose_model_path_to_sdf" "pose_model") sdformat_test_files_get_model_sdf("pose_visual_path_to_sdf" "pose_visual") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) ament_add_gtest(sdf_pose_tests "test/sdf_pose_tests.cpp") target_link_libraries(sdf_pose_tests sdformat_urdf) - target_include_directories(sdf_pose_tests PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + target_include_directories(sdf_pose_tests PRIVATE + "${CMAKE_CURRENT_SOURCE_DIR}/test/include" + "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") endif() diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 597cb4fe..4250b040 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -80,6 +80,14 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) // copy name urdf_model->name_ = sdf_model.Name(); + // TODO(sloretz) what is a model's pose? What does it resolve relative to? + if ("" != sdf_model.PoseRelativeTo() || ignition::math::Pose3d{} != sdf_model.RawPose()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + " tags with are not currently supported by sdformat_urdf"); + return nullptr; + } + // create matching links for (uint64_t l = 0; l < sdf_model.LinkCount(); ++l) { const sdf::Link * sdf_link = sdf_model.LinkByIndex(l); diff --git a/test/include/test_tools.hpp b/test/include/test_tools.hpp new file mode 100644 index 00000000..bec293d5 --- /dev/null +++ b/test/include/test_tools.hpp @@ -0,0 +1,56 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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. + +#ifndef TEST_TOOLS_HPP_ +#define TEST_TOOLS_HPP_ + +#include + +#include +#include +#include +#include + +inline +std::string +get_file(const char * path) +{ + std::ifstream file_reader(path, std::ifstream::in); + std::stringstream buffer; + buffer << file_reader.rdbuf(); + return buffer.str(); +} + +#define EXPECT_POSE(expected_ign, actual_urdf) \ + do { \ + const auto actual_ign = ignition::math::Pose3d{ \ + actual_urdf.position.x, \ + actual_urdf.position.y, \ + actual_urdf.position.z, \ + actual_urdf.rotation.w, \ + actual_urdf.rotation.x, \ + actual_urdf.rotation.y, \ + actual_urdf.rotation.z}; \ + EXPECT_EQ(expected_ign, actual_ign); \ + } while (false) + +std::ostream & operator<<(std::ostream & os, const sdf::Errors & errors) +{ + for (const auto & error : errors) { + os << error; + } + return os; +} + +#endif // TEST_TOOLS_HPP_ diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 7205c8cb..553a9f8e 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -18,20 +18,7 @@ #define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" #define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" #define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" +#define POSE_MODEL_PATH_TO_SDF "@pose_model_path_to_sdf@" #define POSE_VISUAL_PATH_TO_SDF "@pose_visual_path_to_sdf@" -#include -#include -#include - -inline -std::string -get_file(const char * path) -{ - std::ifstream file_reader(path, std::ifstream::in); - std::stringstream buffer; - buffer << file_reader.rdbuf(); - return buffer.str(); -} - #endif // SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 6415ed12..eadbf431 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -21,27 +21,14 @@ #include #include "sdf_paths.hpp" - - -#define EXPECT_POSE(expected_ign, actual_urdf) \ - do { \ - const auto actual_ign = ignition::math::Pose3d{ \ - actual_urdf.position.x, \ - actual_urdf.position.y, \ - actual_urdf.position.z, \ - actual_urdf.rotation.w, \ - actual_urdf.rotation.x, \ - actual_urdf.rotation.y, \ - actual_urdf.rotation.z}; \ - EXPECT_EQ(expected_ign, actual_ign); \ - } while (false) +#include "test_tools.hpp" TEST(Pose, pose_collision) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(POSE_COLLISION_PATH_TO_SDF), errors); - EXPECT_TRUE(errors.empty()); + EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); EXPECT_EQ("pose_collision", model->getName()); @@ -62,7 +49,7 @@ TEST(Pose, pose_inertial) sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(POSE_INERTIAL_PATH_TO_SDF), errors); - EXPECT_TRUE(errors.empty()); + EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); EXPECT_EQ("pose_inertial", model->getName()); @@ -83,7 +70,7 @@ TEST(Pose, pose_link) sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(POSE_LINK_PATH_TO_SDF), errors); - EXPECT_TRUE(errors.empty()); + EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); EXPECT_EQ("pose_link", model->getName()); @@ -100,12 +87,21 @@ TEST(Pose, pose_link) EXPECT_POSE(expected_pose, link->collision->origin); } +TEST(Pose, pose_model) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_MODEL_PATH_TO_SDF), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} + TEST(Pose, pose_visual) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(POSE_VISUAL_PATH_TO_SDF), errors); - EXPECT_TRUE(errors.empty()); + EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); EXPECT_EQ("pose_visual", model->getName()); From 467fbd99dd6ce576f642fb74595593dafad535e4 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 25 Sep 2020 09:07:50 -0700 Subject: [PATCH 031/152] Replace todo with explanation Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 4250b040..58099075 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -80,7 +80,8 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) // copy name urdf_model->name_ = sdf_model.Name(); - // TODO(sloretz) what is a model's pose? What does it resolve relative to? + // A model's pose is the location of the model in a larger context, like a world or parent model + // It doesn't make sense in the context of a robot description. if ("" != sdf_model.PoseRelativeTo() || ignition::math::Pose3d{} != sdf_model.RawPose()) { errors.emplace_back( sdf::ErrorCode::STRING_READ, From 4cfbcbc2eb5f3b526a35624555ff9da7442fc318 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 25 Sep 2020 09:57:51 -0700 Subject: [PATCH 032/152] Add pose_link_all test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 28 ++++++++++++++++++++++++++++ 3 files changed, 30 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index a54b3090..5f236f08 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -75,6 +75,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") + sdformat_test_files_get_model_sdf("pose_link_all_path_to_sdf" "pose_link_all") sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") sdformat_test_files_get_model_sdf("pose_model_path_to_sdf" "pose_model") sdformat_test_files_get_model_sdf("pose_visual_path_to_sdf" "pose_visual") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 553a9f8e..8be34710 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -17,6 +17,7 @@ #define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" #define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" +#define POSE_LINK_ALL_PATH_TO_SDF "@pose_link_all_path_to_sdf@" #define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" #define POSE_MODEL_PATH_TO_SDF "@pose_model_path_to_sdf@" #define POSE_VISUAL_PATH_TO_SDF "@pose_visual_path_to_sdf@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index eadbf431..d759c287 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -87,6 +87,34 @@ TEST(Pose, pose_link) EXPECT_POSE(expected_pose, link->collision->origin); } +TEST(Pose, pose_link_all) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_LINK_ALL_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + EXPECT_EQ("pose_link_all", model->getName()); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + // URDF link C++ structure does not have an origin - instead the pose of the + // link should be added to the visual, collision, and inertial members. + const ignition::math::Pose3d link_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d expected_inertial_pose = + link_pose + ignition::math::Pose3d{0.05, 0.1, 0.2, 0.4, 0.5, 0.6}; + const ignition::math::Pose3d expected_collision_pose = + link_pose + ignition::math::Pose3d{0.04, 0.8, 0.16, 0.3, 0.4, 0.5}; + const ignition::math::Pose3d expected_visual_pose = + link_pose + ignition::math::Pose3d{0.03, 0.6, 0.12, 0.2, 0.3, 0.4}; + + EXPECT_POSE(expected_inertial_pose, link->inertial->origin); + EXPECT_POSE(expected_visual_pose, link->visual->origin); + EXPECT_POSE(expected_collision_pose, link->collision->origin); +} + TEST(Pose, pose_model) { sdf::Errors errors; From f96ec4c7509d2d024cce53b26ed98bd9012c7d62 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 25 Sep 2020 14:03:49 -0700 Subject: [PATCH 033/152] Assert model name is correct Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index d759c287..074bc582 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -30,7 +30,7 @@ TEST(Pose, pose_collision) get_file(POSE_COLLISION_PATH_TO_SDF), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); - EXPECT_EQ("pose_collision", model->getName()); + ASSERT_EQ("pose_collision", model->getName()); ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); @@ -51,7 +51,7 @@ TEST(Pose, pose_inertial) get_file(POSE_INERTIAL_PATH_TO_SDF), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); - EXPECT_EQ("pose_inertial", model->getName()); + ASSERT_EQ("pose_inertial", model->getName()); ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); @@ -72,7 +72,7 @@ TEST(Pose, pose_link) get_file(POSE_LINK_PATH_TO_SDF), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); - EXPECT_EQ("pose_link", model->getName()); + ASSERT_EQ("pose_link", model->getName()); ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); @@ -94,7 +94,7 @@ TEST(Pose, pose_link_all) get_file(POSE_LINK_ALL_PATH_TO_SDF), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); - EXPECT_EQ("pose_link_all", model->getName()); + ASSERT_EQ("pose_link_all", model->getName()); ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); @@ -131,7 +131,7 @@ TEST(Pose, pose_visual) get_file(POSE_VISUAL_PATH_TO_SDF), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); - EXPECT_EQ("pose_visual", model->getName()); + ASSERT_EQ("pose_visual", model->getName()); ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); From 77d29609932d0fe50ea5ee5a93011afc6858f2dc Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 25 Sep 2020 16:30:54 -0700 Subject: [PATCH 034/152] Add pose_link_in_frame test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 21 +++++++++++++++++++++ 3 files changed, 23 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5f236f08..6f4181ff 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -76,6 +76,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") sdformat_test_files_get_model_sdf("pose_link_all_path_to_sdf" "pose_link_all") + sdformat_test_files_get_model_sdf("pose_link_in_frame_path_to_sdf" "pose_link_in_frame") sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") sdformat_test_files_get_model_sdf("pose_model_path_to_sdf" "pose_model") sdformat_test_files_get_model_sdf("pose_visual_path_to_sdf" "pose_visual") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 8be34710..47bf9fc4 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -18,6 +18,7 @@ #define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" #define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" #define POSE_LINK_ALL_PATH_TO_SDF "@pose_link_all_path_to_sdf@" +#define POSE_LINK_IN_FRAME_PATH_TO_SDF "@pose_link_in_frame_path_to_sdf@" #define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" #define POSE_MODEL_PATH_TO_SDF "@pose_model_path_to_sdf@" #define POSE_VISUAL_PATH_TO_SDF "@pose_visual_path_to_sdf@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 074bc582..088c2748 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -115,6 +115,27 @@ TEST(Pose, pose_link_all) EXPECT_POSE(expected_collision_pose, link->collision->origin); } +TEST(Pose, pose_link_in_frame) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_LINK_IN_FRAME_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("pose_link_in_frame", model->getName()); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + const ignition::math::Pose3d frame_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d expected_pose = + ignition::math::Pose3d{0.2, 0.4, 0.8, 0.2, 0.3, 0.4} + frame_pose; + EXPECT_POSE(expected_pose, link->inertial->origin); + EXPECT_POSE(expected_pose, link->visual->origin); + EXPECT_POSE(expected_pose, link->collision->origin); +} + TEST(Pose, pose_model) { sdf::Errors errors; From 57703ac0e93940aaff38c8287fc48df057ff2c7b Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 25 Sep 2020 16:41:41 -0700 Subject: [PATCH 035/152] Add pose_collision_in_frame test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 23 +++++++++++++++++++++++ 3 files changed, 25 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6f4181ff..1c88e2a7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + sdformat_test_files_get_model_sdf("pose_collision_in_frame_path_to_sdf" "pose_collision_in_frame") sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") sdformat_test_files_get_model_sdf("pose_link_all_path_to_sdf" "pose_link_all") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 47bf9fc4..40f4fd68 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,6 +15,7 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define POSE_COLLISION_IN_FRAME_PATH_TO_SDF "@pose_collision_in_frame_path_to_sdf@" #define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" #define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" #define POSE_LINK_ALL_PATH_TO_SDF "@pose_link_all_path_to_sdf@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 088c2748..71bda171 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -44,6 +44,29 @@ TEST(Pose, pose_collision) EXPECT_POSE(expected_collision_pose, link->collision->origin); } +TEST(Pose, pose_collision_in_frame) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_COLLISION_IN_FRAME_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("pose_collision_in_frame", model->getName()); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + const ignition::math::Pose3d frame_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d expected_collision_pose = + ignition::math::Pose3d{0.2, 0.4, 0.8, 0.2, 0.3, 0.4} + frame_pose; + const ignition::math::Pose3d expected_other_pose{0, 0, 0, 0, 0, 0}; + + EXPECT_POSE(expected_other_pose, link->inertial->origin); + EXPECT_POSE(expected_other_pose, link->visual->origin); + EXPECT_POSE(expected_collision_pose, link->collision->origin); +} + TEST(Pose, pose_inertial) { sdf::Errors errors; From e3b00ed5169833874a7271dad975e44057b477c9 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 25 Sep 2020 16:50:38 -0700 Subject: [PATCH 036/152] Add pose_visual_in_frame test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 23 +++++++++++++++++++++++ 3 files changed, 25 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1c88e2a7..0d5b412b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -80,6 +80,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("pose_link_in_frame_path_to_sdf" "pose_link_in_frame") sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") sdformat_test_files_get_model_sdf("pose_model_path_to_sdf" "pose_model") + sdformat_test_files_get_model_sdf("pose_visual_in_frame_path_to_sdf" "pose_visual_in_frame") sdformat_test_files_get_model_sdf("pose_visual_path_to_sdf" "pose_visual") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 40f4fd68..2ef8b5f7 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -22,6 +22,7 @@ #define POSE_LINK_IN_FRAME_PATH_TO_SDF "@pose_link_in_frame_path_to_sdf@" #define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" #define POSE_MODEL_PATH_TO_SDF "@pose_model_path_to_sdf@" +#define POSE_VISUAL_IN_FRAME_PATH_TO_SDF "@pose_visual_in_frame_path_to_sdf@" #define POSE_VISUAL_PATH_TO_SDF "@pose_visual_path_to_sdf@" #endif // SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 71bda171..90bd8e52 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -188,3 +188,26 @@ TEST(Pose, pose_visual) EXPECT_POSE(expected_visual_pose, link->visual->origin); EXPECT_POSE(expected_other_pose, link->collision->origin); } + +TEST(Pose, pose_visual_in_frame) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_VISUAL_IN_FRAME_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("pose_visual_in_frame", model->getName()); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + const ignition::math::Pose3d frame_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d expected_visual_pose = + ignition::math::Pose3d{0.2, 0.4, 0.8, 0.2, 0.3, 0.4} + frame_pose; + const ignition::math::Pose3d expected_other_pose{0, 0, 0, 0, 0, 0}; + + EXPECT_POSE(expected_other_pose, link->inertial->origin); + EXPECT_POSE(expected_visual_pose, link->visual->origin); + EXPECT_POSE(expected_other_pose, link->collision->origin); +} From b14eeb58e980e9cfec70e2b62581b69ce752d34c Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 Sep 2020 15:01:40 -0700 Subject: [PATCH 037/152] Add skipped pose_inertial_in_frame test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 25 +++++++++++++++++++++++++ 3 files changed, 27 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 0d5b412b..a61c7ecf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -75,6 +75,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("pose_collision_in_frame_path_to_sdf" "pose_collision_in_frame") sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") + sdformat_test_files_get_model_sdf("pose_inertial_in_frame_path_to_sdf" "pose_inertial_in_frame") sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") sdformat_test_files_get_model_sdf("pose_link_all_path_to_sdf" "pose_link_all") sdformat_test_files_get_model_sdf("pose_link_in_frame_path_to_sdf" "pose_link_in_frame") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 2ef8b5f7..0b293b2a 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -17,6 +17,7 @@ #define POSE_COLLISION_IN_FRAME_PATH_TO_SDF "@pose_collision_in_frame_path_to_sdf@" #define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" +#define POSE_INERTIAL_IN_FRAME_PATH_TO_SDF "@pose_inertial_in_frame_path_to_sdf@" #define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" #define POSE_LINK_ALL_PATH_TO_SDF "@pose_link_all_path_to_sdf@" #define POSE_LINK_IN_FRAME_PATH_TO_SDF "@pose_link_in_frame_path_to_sdf@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 90bd8e52..47b7149a 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -88,6 +88,31 @@ TEST(Pose, pose_inertial) EXPECT_POSE(expected_other_pose, link->collision->origin); } +TEST(Pose, pose_inertial_in_frame) +{ + GTEST_SKIP() << "https://github.com/osrf/sdformat/issues/380"; + + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_INERTIAL_IN_FRAME_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("pose_inertial_in_frame", model->getName()); + + ASSERT_EQ(1u, model->links_.size()); + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + + const ignition::math::Pose3d frame_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d expected_inertial_pose = + ignition::math::Pose3d{0.2, 0.4, 0.8, 0.2, 0.3, 0.4} + frame_pose; + const ignition::math::Pose3d expected_other_pose{0, 0, 0, 0, 0, 0}; + + EXPECT_POSE(expected_inertial_pose, link->inertial->origin); + EXPECT_POSE(expected_other_pose, link->visual->origin); + EXPECT_POSE(expected_other_pose, link->collision->origin); +} + TEST(Pose, pose_link) { sdf::Errors errors; From bcb85e232cd555d60fe2937c8b017774475dd655 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 30 Sep 2020 11:08:39 -0700 Subject: [PATCH 038/152] Depend on sdformat Signed-off-by: Shane Loretz --- package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/package.xml b/package.xml index cf2eb394..ce76f767 100644 --- a/package.xml +++ b/package.xml @@ -19,6 +19,8 @@ urdf + sdformat + liburdfdom-headers-dev pluginlib tinyxml2_vendor From 276b013b225a01bc5b1d09f1b5446450ffaced5c Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 30 Sep 2020 11:13:11 -0700 Subject: [PATCH 039/152] Fix link poses of child links Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 28 +++++++++++++++++++++++----- 1 file changed, 23 insertions(+), 5 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 58099075..685f81b5 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -27,8 +27,12 @@ namespace sdformat_urdf { /// \brief Convert SDFormat Link to URDF Link +/// \param[in] sdf_link the SDFormat link instance to convert +/// \param[in] joint_frame the name of the only joint who has this link as a child, or empty string +/// if no such joint exists. +/// \param[out] errors any errors encountered while trying to convert the link urdf::LinkSharedPtr -convert_link(const sdf::Link & sdf_link, sdf::Errors & errors); +convert_link(const sdf::Link & sdf_link, const std::string & joint_frame, sdf::Errors & errors); /// \brief Convert SDFormat Joint to URDF Joint urdf::JointSharedPtr @@ -100,7 +104,19 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) return nullptr; } - auto pair = urdf_model->links_.emplace(sdf_link->Name(), convert_link(*sdf_link, errors)); + // URDF link pose is either relative to __model__ or to a joint + std::string relative_joint_name{""}; + for (uint64_t j = 0; j < sdf_model.JointCount(); ++j) { + const sdf::Joint * sdf_joint = sdf_model.JointByIndex(j); + if (sdf_joint && sdf_joint->ChildLinkName() == sdf_link->Name()) { + relative_joint_name = sdf_joint->Name(); + break; + } + } + + auto pair = urdf_model->links_.emplace( + sdf_link->Name(), + convert_link(*sdf_link, relative_joint_name, errors)); if (!pair.second) { errors.emplace_back( @@ -243,16 +259,18 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) } urdf::LinkSharedPtr -sdformat_urdf::convert_link(const sdf::Link & sdf_link, sdf::Errors & errors) +sdformat_urdf::convert_link( + const sdf::Link & sdf_link, const std::string & relative_joint_name, sdf::Errors & errors) { urdf::LinkSharedPtr urdf_link = std::make_shared(); urdf_link->name = sdf_link.Name(); - // Link pose is by default relative to the model + // SDFormat Link pose is by default relative to the model, but in URDF it is relative + // to either the model or to a joint having it as a child ignition::math::Pose3d link_pose; { - sdf::Errors pose_errors = sdf_link.SemanticPose().Resolve(link_pose); + sdf::Errors pose_errors = sdf_link.SemanticPose().Resolve(link_pose, relative_joint_name); if (!pose_errors.empty()) { errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( From 743b0caee5909ac469546c9c7d5379fa9b448e0a Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 30 Sep 2020 11:13:34 -0700 Subject: [PATCH 040/152] Add test for model with joint pose Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 37 +++++++++++++++++++++++++++++++++++++ 3 files changed, 39 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index a61c7ecf..101dd38c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -77,6 +77,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") sdformat_test_files_get_model_sdf("pose_inertial_in_frame_path_to_sdf" "pose_inertial_in_frame") sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") + sdformat_test_files_get_model_sdf("pose_joint_path_to_sdf" "pose_joint") sdformat_test_files_get_model_sdf("pose_link_all_path_to_sdf" "pose_link_all") sdformat_test_files_get_model_sdf("pose_link_in_frame_path_to_sdf" "pose_link_in_frame") sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 0b293b2a..6a79bf6a 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -19,6 +19,7 @@ #define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" #define POSE_INERTIAL_IN_FRAME_PATH_TO_SDF "@pose_inertial_in_frame_path_to_sdf@" #define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" +#define POSE_JOINT_PATH_TO_SDF "@pose_joint_path_to_sdf@" #define POSE_LINK_ALL_PATH_TO_SDF "@pose_link_all_path_to_sdf@" #define POSE_LINK_IN_FRAME_PATH_TO_SDF "@pose_link_in_frame_path_to_sdf@" #define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 47b7149a..c1d20420 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -113,6 +113,43 @@ TEST(Pose, pose_inertial_in_frame) EXPECT_POSE(expected_other_pose, link->collision->origin); } +TEST(Pose, pose_joint) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_JOINT_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("pose_joint", model->getName()); + + ASSERT_EQ(2u, model->links_.size()); + ASSERT_EQ(1u, model->joints_.size()); + urdf::JointConstSharedPtr joint = model->joints_.begin()->second; + ASSERT_NE(nullptr, joint); + urdf::LinkConstSharedPtr parent_link = model->getLink(joint->parent_link_name); + ASSERT_NE(nullptr, parent_link); + urdf::LinkConstSharedPtr child_link = model->getLink(joint->child_link_name); + ASSERT_NE(nullptr, child_link); + + // In URDF joint is in parent link frame + // The child link in URDF lives in the joint frame + const ignition::math::Pose3d model_to_parent_in_model(0, 0, 0, 0, 0, 0); + const ignition::math::Pose3d model_to_child_in_model(0, 0, 0, 0, 0, 0); + const ignition::math::Pose3d model_to_joint_in_model(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d parent_to_joint_in_parent = + model_to_joint_in_model - model_to_parent_in_model; + const ignition::math::Pose3d joint_to_child_in_joint = + model_to_child_in_model - model_to_joint_in_model; + + EXPECT_POSE(parent_to_joint_in_parent, joint->parent_to_joint_origin_transform); + + // URDF link C++ structure does not have an origin - instead the pose of the + // link should be added to the visual, collision, and inertial members. + EXPECT_POSE(joint_to_child_in_joint, child_link->inertial->origin); + EXPECT_POSE(joint_to_child_in_joint, child_link->visual->origin); + EXPECT_POSE(joint_to_child_in_joint, child_link->collision->origin); +} + TEST(Pose, pose_link) { sdf::Errors errors; From 5ea4bbb0176b84db7f9fda176fe270ba4da978d1 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 30 Sep 2020 11:41:43 -0700 Subject: [PATCH 041/152] Remove unused variable Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index c1d20420..26fd7a47 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -126,8 +126,6 @@ TEST(Pose, pose_joint) ASSERT_EQ(1u, model->joints_.size()); urdf::JointConstSharedPtr joint = model->joints_.begin()->second; ASSERT_NE(nullptr, joint); - urdf::LinkConstSharedPtr parent_link = model->getLink(joint->parent_link_name); - ASSERT_NE(nullptr, parent_link); urdf::LinkConstSharedPtr child_link = model->getLink(joint->child_link_name); ASSERT_NE(nullptr, child_link); @@ -136,6 +134,7 @@ TEST(Pose, pose_joint) const ignition::math::Pose3d model_to_parent_in_model(0, 0, 0, 0, 0, 0); const ignition::math::Pose3d model_to_child_in_model(0, 0, 0, 0, 0, 0); const ignition::math::Pose3d model_to_joint_in_model(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d parent_to_joint_in_parent = model_to_joint_in_model - model_to_parent_in_model; const ignition::math::Pose3d joint_to_child_in_joint = From db3a64137963d42cbbb0290f3a1fbd9783172325 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 30 Sep 2020 11:46:32 -0700 Subject: [PATCH 042/152] Add test for model with joint pose in frame Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 39 +++++++++++++++++++++++++++++++++++++++ 3 files changed, 41 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 101dd38c..fe91af5f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -77,6 +77,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") sdformat_test_files_get_model_sdf("pose_inertial_in_frame_path_to_sdf" "pose_inertial_in_frame") sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") + sdformat_test_files_get_model_sdf("pose_joint_in_frame_path_to_sdf" "pose_joint_in_frame") sdformat_test_files_get_model_sdf("pose_joint_path_to_sdf" "pose_joint") sdformat_test_files_get_model_sdf("pose_link_all_path_to_sdf" "pose_link_all") sdformat_test_files_get_model_sdf("pose_link_in_frame_path_to_sdf" "pose_link_in_frame") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 6a79bf6a..fdf51054 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -19,6 +19,7 @@ #define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" #define POSE_INERTIAL_IN_FRAME_PATH_TO_SDF "@pose_inertial_in_frame_path_to_sdf@" #define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" +#define POSE_JOINT_IN_FRAME_PATH_TO_SDF "@pose_joint_in_frame_path_to_sdf@" #define POSE_JOINT_PATH_TO_SDF "@pose_joint_path_to_sdf@" #define POSE_LINK_ALL_PATH_TO_SDF "@pose_link_all_path_to_sdf@" #define POSE_LINK_IN_FRAME_PATH_TO_SDF "@pose_link_in_frame_path_to_sdf@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 26fd7a47..4e0215ae 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -149,6 +149,45 @@ TEST(Pose, pose_joint) EXPECT_POSE(joint_to_child_in_joint, child_link->collision->origin); } +TEST(Pose, pose_joint_in_frame) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(POSE_JOINT_IN_FRAME_PATH_TO_SDF), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("pose_joint_in_frame", model->getName()); + + ASSERT_EQ(2u, model->links_.size()); + ASSERT_EQ(1u, model->joints_.size()); + urdf::JointConstSharedPtr joint = model->joints_.begin()->second; + ASSERT_NE(nullptr, joint); + urdf::LinkConstSharedPtr child_link = model->getLink(joint->child_link_name); + ASSERT_NE(nullptr, child_link); + + // In URDF joint is in parent link frame + // The child link in URDF lives in the joint frame + const ignition::math::Pose3d model_to_parent_in_model(0, 0, 0, 0, 0, 0); + const ignition::math::Pose3d model_to_child_in_model(0, 0, 0, 0, 0, 0); + const ignition::math::Pose3d model_to_frame_in_model(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d frame_to_joint_in_frame(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + + const ignition::math::Pose3d model_to_joint_in_model = + frame_to_joint_in_frame + model_to_frame_in_model; + const ignition::math::Pose3d parent_to_joint_in_parent = + model_to_joint_in_model - model_to_parent_in_model; + const ignition::math::Pose3d joint_to_child_in_joint = + model_to_child_in_model - model_to_joint_in_model; + + EXPECT_POSE(parent_to_joint_in_parent, joint->parent_to_joint_origin_transform); + + // URDF link C++ structure does not have an origin - instead the pose of the + // link should be added to the visual, collision, and inertial members. + EXPECT_POSE(joint_to_child_in_joint, child_link->inertial->origin); + EXPECT_POSE(joint_to_child_in_joint, child_link->visual->origin); + EXPECT_POSE(joint_to_child_in_joint, child_link->collision->origin); +} + TEST(Pose, pose_link) { sdf::Errors errors; From 1134ffba885cc970f64f85a6a567f68c0cf19ec5 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 30 Sep 2020 14:45:04 -0700 Subject: [PATCH 043/152] Rename variables for consistent ordering Signed-off-by: Shane Loretz --- CMakeLists.txt | 24 ++++++++++++------------ test/sdf_paths.hpp.in | 24 ++++++++++++------------ test/sdf_pose_tests.cpp | 24 ++++++++++++------------ 3 files changed, 36 insertions(+), 36 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index fe91af5f..1fdc1ccd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,18 +73,18 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() - sdformat_test_files_get_model_sdf("pose_collision_in_frame_path_to_sdf" "pose_collision_in_frame") - sdformat_test_files_get_model_sdf("pose_collision_path_to_sdf" "pose_collision") - sdformat_test_files_get_model_sdf("pose_inertial_in_frame_path_to_sdf" "pose_inertial_in_frame") - sdformat_test_files_get_model_sdf("pose_inertial_path_to_sdf" "pose_inertial") - sdformat_test_files_get_model_sdf("pose_joint_in_frame_path_to_sdf" "pose_joint_in_frame") - sdformat_test_files_get_model_sdf("pose_joint_path_to_sdf" "pose_joint") - sdformat_test_files_get_model_sdf("pose_link_all_path_to_sdf" "pose_link_all") - sdformat_test_files_get_model_sdf("pose_link_in_frame_path_to_sdf" "pose_link_in_frame") - sdformat_test_files_get_model_sdf("pose_link_path_to_sdf" "pose_link") - sdformat_test_files_get_model_sdf("pose_model_path_to_sdf" "pose_model") - sdformat_test_files_get_model_sdf("pose_visual_in_frame_path_to_sdf" "pose_visual_in_frame") - sdformat_test_files_get_model_sdf("pose_visual_path_to_sdf" "pose_visual") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision" "pose_collision") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision_in_frame" "pose_collision_in_frame") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_inertial" "pose_inertial") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_inertial_in_frame" "pose_inertial_in_frame") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_joint" "pose_joint") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_joint_in_frame" "pose_joint_in_frame") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_link" "pose_link") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_link_all" "pose_link_all") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_link_in_frame" "pose_link_in_frame") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_model" "pose_model") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_visual" "pose_visual") + sdformat_test_files_get_model_sdf("path_to_sdf_pose_visual_in_frame" "pose_visual_in_frame") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) ament_add_gtest(sdf_pose_tests "test/sdf_pose_tests.cpp") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index fdf51054..561275ec 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,17 +15,17 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ -#define POSE_COLLISION_IN_FRAME_PATH_TO_SDF "@pose_collision_in_frame_path_to_sdf@" -#define POSE_COLLISION_PATH_TO_SDF "@pose_collision_path_to_sdf@" -#define POSE_INERTIAL_IN_FRAME_PATH_TO_SDF "@pose_inertial_in_frame_path_to_sdf@" -#define POSE_INERTIAL_PATH_TO_SDF "@pose_inertial_path_to_sdf@" -#define POSE_JOINT_IN_FRAME_PATH_TO_SDF "@pose_joint_in_frame_path_to_sdf@" -#define POSE_JOINT_PATH_TO_SDF "@pose_joint_path_to_sdf@" -#define POSE_LINK_ALL_PATH_TO_SDF "@pose_link_all_path_to_sdf@" -#define POSE_LINK_IN_FRAME_PATH_TO_SDF "@pose_link_in_frame_path_to_sdf@" -#define POSE_LINK_PATH_TO_SDF "@pose_link_path_to_sdf@" -#define POSE_MODEL_PATH_TO_SDF "@pose_model_path_to_sdf@" -#define POSE_VISUAL_IN_FRAME_PATH_TO_SDF "@pose_visual_in_frame_path_to_sdf@" -#define POSE_VISUAL_PATH_TO_SDF "@pose_visual_path_to_sdf@" +#define PATH_TO_SDF_POSE_COLLISION "@path_to_sdf_pose_collision@" +#define PATH_TO_SDF_POSE_COLLISION_IN_FRAME "@path_to_sdf_pose_collision_in_frame@" +#define PATH_TO_SDF_POSE_INERTIAL "@path_to_sdf_pose_inertial@" +#define PATH_TO_SDF_POSE_INERTIAL_IN_FRAME "@path_to_sdf_pose_inertial_in_frame@" +#define PATH_TO_SDF_POSE_JOINT "@path_to_sdf_pose_joint@" +#define PATH_TO_SDF_POSE_JOINT_IN_FRAME "@path_to_sdf_pose_joint_in_frame@" +#define PATH_TO_SDF_POSE_LINK "@path_to_sdf_pose_link@" +#define PATH_TO_SDF_POSE_LINK_ALL "@path_to_sdf_pose_link_all@" +#define PATH_TO_SDF_POSE_LINK_IN_FRAME "@path_to_sdf_pose_link_in_frame@" +#define PATH_TO_SDF_POSE_MODEL "@path_to_sdf_pose_model@" +#define PATH_TO_SDF_POSE_VISUAL "@path_to_sdf_pose_visual@" +#define PATH_TO_SDF_POSE_VISUAL_IN_FRAME "@path_to_sdf_pose_visual_in_frame@" #endif // SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 4e0215ae..17d03229 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -27,7 +27,7 @@ TEST(Pose, pose_collision) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_COLLISION_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_COLLISION), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_collision", model->getName()); @@ -48,7 +48,7 @@ TEST(Pose, pose_collision_in_frame) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_COLLISION_IN_FRAME_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_COLLISION_IN_FRAME), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_collision_in_frame", model->getName()); @@ -71,7 +71,7 @@ TEST(Pose, pose_inertial) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_INERTIAL_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_INERTIAL), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_inertial", model->getName()); @@ -94,7 +94,7 @@ TEST(Pose, pose_inertial_in_frame) sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_INERTIAL_IN_FRAME_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_INERTIAL_IN_FRAME), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_inertial_in_frame", model->getName()); @@ -117,7 +117,7 @@ TEST(Pose, pose_joint) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_JOINT_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_JOINT), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_joint", model->getName()); @@ -153,7 +153,7 @@ TEST(Pose, pose_joint_in_frame) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_JOINT_IN_FRAME_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_JOINT_IN_FRAME), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_joint_in_frame", model->getName()); @@ -192,7 +192,7 @@ TEST(Pose, pose_link) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_LINK_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_LINK), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_link", model->getName()); @@ -214,7 +214,7 @@ TEST(Pose, pose_link_all) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_LINK_ALL_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_LINK_ALL), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_link_all", model->getName()); @@ -242,7 +242,7 @@ TEST(Pose, pose_link_in_frame) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_LINK_IN_FRAME_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_LINK_IN_FRAME), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_link_in_frame", model->getName()); @@ -263,7 +263,7 @@ TEST(Pose, pose_model) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_MODEL_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_MODEL), errors); EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } @@ -272,7 +272,7 @@ TEST(Pose, pose_visual) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_VISUAL_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_VISUAL), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_visual", model->getName()); @@ -293,7 +293,7 @@ TEST(Pose, pose_visual_in_frame) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(POSE_VISUAL_IN_FRAME_PATH_TO_SDF), errors); + get_file(PATH_TO_SDF_POSE_VISUAL_IN_FRAME), errors); EXPECT_TRUE(errors.empty()) << errors; ASSERT_TRUE(model); ASSERT_EQ("pose_visual_in_frame", model->getName()); From 14bc1d2c02b4885333e1a8896b678a7f8ace85ec Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 1 Oct 2020 12:23:41 -0700 Subject: [PATCH 044/152] Fix fame names in calculating joint pose Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 17d03229..66b0b0e9 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -133,12 +133,13 @@ TEST(Pose, pose_joint) // The child link in URDF lives in the joint frame const ignition::math::Pose3d model_to_parent_in_model(0, 0, 0, 0, 0, 0); const ignition::math::Pose3d model_to_child_in_model(0, 0, 0, 0, 0, 0); - const ignition::math::Pose3d model_to_joint_in_model(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d child_to_joint_in_child(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d parent_to_child_in_parent = + model_to_child_in_model - model_to_parent_in_model; const ignition::math::Pose3d parent_to_joint_in_parent = - model_to_joint_in_model - model_to_parent_in_model; - const ignition::math::Pose3d joint_to_child_in_joint = - model_to_child_in_model - model_to_joint_in_model; + child_to_joint_in_child + parent_to_child_in_parent; + const ignition::math::Pose3d joint_to_child_in_joint = -child_to_joint_in_child; EXPECT_POSE(parent_to_joint_in_parent, joint->parent_to_joint_origin_transform); From 8d8441bfbe58800214e395e5763bca42123fa7ca Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 15:40:24 -0700 Subject: [PATCH 045/152] URDF link frames are coincident with joint frames And the root link pose has no effect on the URDF output except that it changes the relative locations of other links with the root link. The SDF link pose cannot be expressed in URDF C++ structures without adding dummy links, but this does not do that. Signed-off-by: Shane Loretz Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 685f81b5..56bffd74 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -219,9 +219,16 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) // Append to child joints urdf_parent_link->child_joints.push_back(urdf_joint); - // Set the joint origin to the transform from the joint to the parent link + // SDFormat joint pose is relative to the child sdformat link + // URDF joint pose is relative to the parent urdf link, which is the the frame of the + // previous urdf joint + std::string parent_frame_name{sdf_parent_link->Name()}; + if (urdf_parent_link->parent_joint) { + parent_frame_name = urdf_parent_link->parent_joint->name; + } + ignition::math::Pose3d joint_pose; - pose_errors = sdf_joint->SemanticPose().Resolve(joint_pose, sdf_parent_link->Name()); + pose_errors = sdf_joint->SemanticPose().Resolve(joint_pose, parent_frame_name); if (!pose_errors.empty()) { errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( @@ -266,10 +273,11 @@ sdformat_urdf::convert_link( urdf_link->name = sdf_link.Name(); - // SDFormat Link pose is by default relative to the model, but in URDF it is relative - // to either the model or to a joint having it as a child + // joint to link in joint if this is not the root link, else identity + // The pose of the root link does not matter because there is no equivalent in URDF ignition::math::Pose3d link_pose; - { + if (!relative_joint_name.empty()) { + // urdf link pose is the location of the joint having it as a child sdf::Errors pose_errors = sdf_link.SemanticPose().Resolve(link_pose, relative_joint_name); if (!pose_errors.empty()) { errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); From 58e865c261c2f31c9c5f5aa95240f7b652d28015 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 15:41:44 -0700 Subject: [PATCH 046/152] Add pose_chain test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/sdf_paths.hpp.in | 1 + test/sdf_pose_tests.cpp | 81 +++++++++++++++++++++++++++++++++++++++++ 3 files changed, 83 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1fdc1ccd..9f51f548 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision" "pose_collision") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision_in_frame" "pose_collision_in_frame") sdformat_test_files_get_model_sdf("path_to_sdf_pose_inertial" "pose_inertial") diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 561275ec..43d92ce3 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,6 +15,7 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" #define PATH_TO_SDF_POSE_COLLISION "@path_to_sdf_pose_collision@" #define PATH_TO_SDF_POSE_COLLISION_IN_FRAME "@path_to_sdf_pose_collision_in_frame@" #define PATH_TO_SDF_POSE_INERTIAL "@path_to_sdf_pose_inertial@" diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 66b0b0e9..6231aa80 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -23,6 +23,87 @@ #include "sdf_paths.hpp" #include "test_tools.hpp" +TEST(Pose, pose_chain) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_POSE_CHAIN), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("pose_chain", model->getName()); + + ASSERT_EQ(4u, model->links_.size()); + ASSERT_EQ(3u, model->joints_.size()); + + urdf::LinkConstSharedPtr link_1 = model->getLink("pose_chain_link_1"); + ASSERT_NE(nullptr, link_1); + urdf::LinkConstSharedPtr link_2 = model->getLink("pose_chain_link_2"); + ASSERT_NE(nullptr, link_2); + urdf::LinkConstSharedPtr link_3 = model->getLink("pose_chain_link_3"); + ASSERT_NE(nullptr, link_3); + urdf::LinkConstSharedPtr link_4 = model->getLink("pose_chain_link_4"); + ASSERT_NE(nullptr, link_4); + + urdf::JointConstSharedPtr joint_1 = model->getJoint("joint_1"); + ASSERT_NE(nullptr, joint_1); + urdf::JointConstSharedPtr joint_2 = model->getJoint("joint_2"); + ASSERT_NE(nullptr, joint_2); + urdf::JointConstSharedPtr joint_3 = model->getJoint("joint_3"); + ASSERT_NE(nullptr, joint_3); + + const ignition::math::Pose3d model_to_link_1_in_model{0.1, 0.2, 0.3, 0.4, 0.5, 0.6}; + const ignition::math::Pose3d model_to_link_2_in_model{0.2, 0.3, 0.4, 0.5, 0.6, 0.7}; + const ignition::math::Pose3d model_to_link_3_in_model{0.3, 0.4, 0.5, 0.6, 0.7, 0.8}; + const ignition::math::Pose3d model_to_link_4_in_model{0.4, 0.5, 0.6, 0.7, 0.8, 0.9}; + const ignition::math::Pose3d link_2_to_joint_1_in_link_2 {0.9, 0.8, 0.7, 0.6, 0.5, 0.4}; + const ignition::math::Pose3d link_3_to_joint_2_in_link_3{0.8, 0.7, 0.6, 0.5, 0.4, 0.3}; + const ignition::math::Pose3d link_4_to_joint_3_in_link_4{0.7, 0.6, 0.5, 0.4, 0.3, 0.2}; + + const ignition::math::Pose3d model_to_joint_1_in_model = + link_2_to_joint_1_in_link_2 + model_to_link_2_in_model; + const ignition::math::Pose3d model_to_joint_2_in_model = + link_3_to_joint_2_in_link_3 + model_to_link_3_in_model; + const ignition::math::Pose3d model_to_joint_3_in_model = + link_4_to_joint_3_in_link_4 + model_to_link_4_in_model; + + const ignition::math::Pose3d link_1_to_joint_1_in_link_1 = + model_to_joint_1_in_model - model_to_link_1_in_model; + const ignition::math::Pose3d joint_1_to_link_2_in_joint_1 = + model_to_link_2_in_model - model_to_joint_1_in_model; + const ignition::math::Pose3d joint_2_to_link_3_in_joint_2 = + model_to_link_3_in_model - model_to_joint_2_in_model; + const ignition::math::Pose3d joint_3_to_link_4_in_joint_3 = + model_to_link_4_in_model - model_to_joint_3_in_model; + + const ignition::math::Pose3d joint_1_to_joint_2_in_joint_1 = + model_to_joint_2_in_model - model_to_joint_1_in_model; + const ignition::math::Pose3d joint_2_to_joint_3_in_joint_2 = + model_to_joint_3_in_model - model_to_joint_2_in_model; + + EXPECT_POSE(ignition::math::Pose3d::Zero, link_1->inertial->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link_1->visual->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link_1->collision->origin); + + EXPECT_POSE(link_1_to_joint_1_in_link_1, joint_1->parent_to_joint_origin_transform); + + EXPECT_POSE(joint_1_to_link_2_in_joint_1, link_2->inertial->origin); + EXPECT_POSE(joint_1_to_link_2_in_joint_1, link_2->visual->origin); + EXPECT_POSE(joint_1_to_link_2_in_joint_1, link_2->collision->origin); + + EXPECT_POSE(joint_1_to_joint_2_in_joint_1, joint_2->parent_to_joint_origin_transform); + + EXPECT_POSE(joint_2_to_link_3_in_joint_2, link_3->inertial->origin); + EXPECT_POSE(joint_2_to_link_3_in_joint_2, link_3->visual->origin); + EXPECT_POSE(joint_2_to_link_3_in_joint_2, link_3->collision->origin); + + EXPECT_POSE(joint_2_to_joint_3_in_joint_2, joint_3->parent_to_joint_origin_transform); + + EXPECT_POSE(joint_3_to_link_4_in_joint_3, link_4->inertial->origin); + EXPECT_POSE(joint_3_to_link_4_in_joint_3, link_4->visual->origin); + EXPECT_POSE(joint_3_to_link_4_in_joint_3, link_4->collision->origin); +} + + TEST(Pose, pose_collision) { sdf::Errors errors; From 11c707333c9340a770d73c0846c5cfdcbf5d1c74 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:03:11 -0700 Subject: [PATCH 047/152] Clearer description of pose_collision expectations Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 6231aa80..4e9687ce 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -113,15 +113,13 @@ TEST(Pose, pose_collision) ASSERT_TRUE(model); ASSERT_EQ("pose_collision", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - const ignition::math::Pose3d expected_collision_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d expected_other_pose(0, 0, 0, 0, 0, 0); + const ignition::math::Pose3d expected_collision_pose{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; - EXPECT_POSE(expected_other_pose, link->inertial->origin); - EXPECT_POSE(expected_other_pose, link->visual->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->inertial->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->visual->origin); EXPECT_POSE(expected_collision_pose, link->collision->origin); } From b49a80f42eca86e7bd0b4abace534ed665f503f0 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:03:25 -0700 Subject: [PATCH 048/152] Clearer description of pose_collision_in_frame expectations Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 4e9687ce..c3dbcb01 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -132,18 +132,20 @@ TEST(Pose, pose_collision_in_frame) ASSERT_TRUE(model); ASSERT_EQ("pose_collision_in_frame", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - const ignition::math::Pose3d frame_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d expected_collision_pose = - ignition::math::Pose3d{0.2, 0.4, 0.8, 0.2, 0.3, 0.4} + frame_pose; - const ignition::math::Pose3d expected_other_pose{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d model_to_frame_in_model{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; + const ignition::math::Pose3d model_to_link_in_model{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d frame_to_link_in_frame = + model_to_link_in_model - model_to_frame_in_model; + const ignition::math::Pose3d frame_to_collision_in_frame{0.2, 0.4, 0.8, 0.2, 0.3, 0.4}; + const ignition::math::Pose3d link_to_collision_in_link = + frame_to_collision_in_frame - frame_to_link_in_frame; - EXPECT_POSE(expected_other_pose, link->inertial->origin); - EXPECT_POSE(expected_other_pose, link->visual->origin); - EXPECT_POSE(expected_collision_pose, link->collision->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->inertial->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->visual->origin); + EXPECT_POSE(link_to_collision_in_link, link->collision->origin); } TEST(Pose, pose_inertial) From faa7e163f257428ed60a4d662aab04dae4b30273 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:16:51 -0700 Subject: [PATCH 049/152] Clearer pose_inertial* expectations Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 25 +++++++++++++------------ 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index c3dbcb01..f121d7fe 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -157,16 +157,14 @@ TEST(Pose, pose_inertial) ASSERT_TRUE(model); ASSERT_EQ("pose_inertial", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - const ignition::math::Pose3d expected_inertial_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d expected_other_pose(0, 0, 0, 0, 0, 0); + const ignition::math::Pose3d expected_inertial_pose{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; EXPECT_POSE(expected_inertial_pose, link->inertial->origin); - EXPECT_POSE(expected_other_pose, link->visual->origin); - EXPECT_POSE(expected_other_pose, link->collision->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->visual->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->collision->origin); } TEST(Pose, pose_inertial_in_frame) @@ -184,14 +182,17 @@ TEST(Pose, pose_inertial_in_frame) urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - const ignition::math::Pose3d frame_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d expected_inertial_pose = - ignition::math::Pose3d{0.2, 0.4, 0.8, 0.2, 0.3, 0.4} + frame_pose; - const ignition::math::Pose3d expected_other_pose{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d model_to_frame_in_model{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; + const ignition::math::Pose3d model_to_link_in_model{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d frame_to_link_in_frame = + model_to_link_in_model - model_to_frame_in_model; + const ignition::math::Pose3d frame_to_inertial_in_frame{0.2, 0.4, 0.8, 0.2, 0.3, 0.4}; + const ignition::math::Pose3d link_to_inertial_in_link = + frame_to_inertial_in_frame - frame_to_link_in_frame; - EXPECT_POSE(expected_inertial_pose, link->inertial->origin); - EXPECT_POSE(expected_other_pose, link->visual->origin); - EXPECT_POSE(expected_other_pose, link->collision->origin); + EXPECT_POSE(link_to_inertial_in_link, link->inertial->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->visual->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->collision->origin); } TEST(Pose, pose_joint) From 6714d71abb692d10dfb54d9d6b7b6bcab613ce89 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:21:16 -0700 Subject: [PATCH 050/152] Remove unnecessary ASSERT Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index f121d7fe..85d0c34b 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -178,7 +178,6 @@ TEST(Pose, pose_inertial_in_frame) ASSERT_TRUE(model); ASSERT_EQ("pose_inertial_in_frame", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); @@ -204,8 +203,6 @@ TEST(Pose, pose_joint) ASSERT_TRUE(model); ASSERT_EQ("pose_joint", model->getName()); - ASSERT_EQ(2u, model->links_.size()); - ASSERT_EQ(1u, model->joints_.size()); urdf::JointConstSharedPtr joint = model->joints_.begin()->second; ASSERT_NE(nullptr, joint); urdf::LinkConstSharedPtr child_link = model->getLink(joint->child_link_name); From 9ad8bfe65176a05b678d941e3b3155cd1bcc2daf Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:21:37 -0700 Subject: [PATCH 051/152] Initializer lists Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 85d0c34b..cd971019 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -210,9 +210,9 @@ TEST(Pose, pose_joint) // In URDF joint is in parent link frame // The child link in URDF lives in the joint frame - const ignition::math::Pose3d model_to_parent_in_model(0, 0, 0, 0, 0, 0); - const ignition::math::Pose3d model_to_child_in_model(0, 0, 0, 0, 0, 0); - const ignition::math::Pose3d child_to_joint_in_child(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d model_to_parent_in_model{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d model_to_child_in_model{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d child_to_joint_in_child{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; const ignition::math::Pose3d parent_to_child_in_parent = model_to_child_in_model - model_to_parent_in_model; From 08afd02b5169be698aad8be9f85f6af6fc4ba1e8 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:35:50 -0700 Subject: [PATCH 052/152] Remove unnecessary ASSERT Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index cd971019..769d24a2 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -238,8 +238,6 @@ TEST(Pose, pose_joint_in_frame) ASSERT_TRUE(model); ASSERT_EQ("pose_joint_in_frame", model->getName()); - ASSERT_EQ(2u, model->links_.size()); - ASSERT_EQ(1u, model->joints_.size()); urdf::JointConstSharedPtr joint = model->joints_.begin()->second; ASSERT_NE(nullptr, joint); urdf::LinkConstSharedPtr child_link = model->getLink(joint->child_link_name); From cd57fc6674732708473f08a0932281893dd4d47a Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:35:58 -0700 Subject: [PATCH 053/152] Initializer lists Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 769d24a2..77fd75a1 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -245,10 +245,10 @@ TEST(Pose, pose_joint_in_frame) // In URDF joint is in parent link frame // The child link in URDF lives in the joint frame - const ignition::math::Pose3d model_to_parent_in_model(0, 0, 0, 0, 0, 0); - const ignition::math::Pose3d model_to_child_in_model(0, 0, 0, 0, 0, 0); - const ignition::math::Pose3d model_to_frame_in_model(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d frame_to_joint_in_frame(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); + const ignition::math::Pose3d model_to_parent_in_model{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d model_to_child_in_model{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d model_to_frame_in_model{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; + const ignition::math::Pose3d frame_to_joint_in_frame{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; const ignition::math::Pose3d model_to_joint_in_model = frame_to_joint_in_frame + model_to_frame_in_model; From 1a4d195d0c05aa43419c1e1fe9d127dd84d90db3 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:41:33 -0700 Subject: [PATCH 054/152] Fix pose_link* test expectations Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 46 ++++++++++++++++------------------------- 1 file changed, 18 insertions(+), 28 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 77fd75a1..5b644ad8 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -275,17 +275,14 @@ TEST(Pose, pose_link) ASSERT_TRUE(model); ASSERT_EQ("pose_link", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - // URDF link C++ structure does not have an origin - instead the pose of the - // link should be added to the visual, collision, and inertial members. - const ignition::math::Pose3d expected_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - - EXPECT_POSE(expected_pose, link->inertial->origin); - EXPECT_POSE(expected_pose, link->visual->origin); - EXPECT_POSE(expected_pose, link->collision->origin); + // URDF link C++ structure does not have an origin - root link members should be unaffected + // by root link pose + EXPECT_POSE(ignition::math::Pose3d::Zero, link->inertial->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->visual->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->collision->origin); } TEST(Pose, pose_link_all) @@ -297,23 +294,18 @@ TEST(Pose, pose_link_all) ASSERT_TRUE(model); ASSERT_EQ("pose_link_all", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - // URDF link C++ structure does not have an origin - instead the pose of the - // link should be added to the visual, collision, and inertial members. - const ignition::math::Pose3d link_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d expected_inertial_pose = - link_pose + ignition::math::Pose3d{0.05, 0.1, 0.2, 0.4, 0.5, 0.6}; - const ignition::math::Pose3d expected_collision_pose = - link_pose + ignition::math::Pose3d{0.04, 0.8, 0.16, 0.3, 0.4, 0.5}; - const ignition::math::Pose3d expected_visual_pose = - link_pose + ignition::math::Pose3d{0.03, 0.6, 0.12, 0.2, 0.3, 0.4}; + // URDF link C++ structure does not have an origin - root link members should be unaffected + // by root link pose + const ignition::math::Pose3d link_to_inertial_in_link{0.05, 0.1, 0.2, 0.4, 0.5, 0.6}; + const ignition::math::Pose3d link_to_collision_in_link{0.04, 0.8, 0.16, 0.3, 0.4, 0.5}; + const ignition::math::Pose3d link_to_visual_in_link{0.03, 0.6, 0.12, 0.2, 0.3, 0.4}; - EXPECT_POSE(expected_inertial_pose, link->inertial->origin); - EXPECT_POSE(expected_visual_pose, link->visual->origin); - EXPECT_POSE(expected_collision_pose, link->collision->origin); + EXPECT_POSE(link_to_inertial_in_link, link->inertial->origin); + EXPECT_POSE(link_to_visual_in_link, link->visual->origin); + EXPECT_POSE(link_to_collision_in_link, link->collision->origin); } TEST(Pose, pose_link_in_frame) @@ -325,16 +317,14 @@ TEST(Pose, pose_link_in_frame) ASSERT_TRUE(model); ASSERT_EQ("pose_link_in_frame", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - const ignition::math::Pose3d frame_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d expected_pose = - ignition::math::Pose3d{0.2, 0.4, 0.8, 0.2, 0.3, 0.4} + frame_pose; - EXPECT_POSE(expected_pose, link->inertial->origin); - EXPECT_POSE(expected_pose, link->visual->origin); - EXPECT_POSE(expected_pose, link->collision->origin); + // URDF link C++ structure does not have an origin - root link members should be unaffected + // by root link pose + EXPECT_POSE(ignition::math::Pose3d::Zero, link->inertial->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->visual->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->collision->origin); } TEST(Pose, pose_model) From e0d722f35b912ee5fb56c261fcb9b0e5d01ce51e Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:45:40 -0700 Subject: [PATCH 055/152] Clearer pose_visual* test expecations Signed-off-by: Shane Loretz --- test/sdf_pose_tests.cpp | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/test/sdf_pose_tests.cpp b/test/sdf_pose_tests.cpp index 5b644ad8..1d8eed0f 100644 --- a/test/sdf_pose_tests.cpp +++ b/test/sdf_pose_tests.cpp @@ -345,16 +345,14 @@ TEST(Pose, pose_visual) ASSERT_TRUE(model); ASSERT_EQ("pose_visual", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - const ignition::math::Pose3d expected_visual_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d expected_other_pose(0, 0, 0, 0, 0, 0); + const ignition::math::Pose3d expected_visual_pose{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; - EXPECT_POSE(expected_other_pose, link->inertial->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->inertial->origin); EXPECT_POSE(expected_visual_pose, link->visual->origin); - EXPECT_POSE(expected_other_pose, link->collision->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->collision->origin); } TEST(Pose, pose_visual_in_frame) @@ -366,16 +364,18 @@ TEST(Pose, pose_visual_in_frame) ASSERT_TRUE(model); ASSERT_EQ("pose_visual_in_frame", model->getName()); - ASSERT_EQ(1u, model->links_.size()); urdf::LinkConstSharedPtr link = model->getRoot(); ASSERT_NE(nullptr, link); - const ignition::math::Pose3d frame_pose(0.05, 0.1, 0.2, 0.1, 0.2, 0.3); - const ignition::math::Pose3d expected_visual_pose = - ignition::math::Pose3d{0.2, 0.4, 0.8, 0.2, 0.3, 0.4} + frame_pose; - const ignition::math::Pose3d expected_other_pose{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d model_to_frame_in_model{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; + const ignition::math::Pose3d model_to_link_in_model{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d frame_to_link_in_frame = + model_to_link_in_model - model_to_frame_in_model; + const ignition::math::Pose3d frame_to_visual_in_frame{0.2, 0.4, 0.8, 0.2, 0.3, 0.4}; + const ignition::math::Pose3d link_to_visual_in_link = + frame_to_visual_in_frame - frame_to_link_in_frame; - EXPECT_POSE(expected_other_pose, link->inertial->origin); - EXPECT_POSE(expected_visual_pose, link->visual->origin); - EXPECT_POSE(expected_other_pose, link->collision->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->inertial->origin); + EXPECT_POSE(link_to_visual_in_link, link->visual->origin); + EXPECT_POSE(ignition::math::Pose3d::Zero, link->collision->origin); } From 184393f3c453d5ed04721efc59fd90ac75500af6 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:53:25 -0700 Subject: [PATCH 056/152] Shorter file name Signed-off-by: Shane Loretz --- test/{sdf_pose_tests.cpp => pose_tests.cpp} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename test/{sdf_pose_tests.cpp => pose_tests.cpp} (100%) diff --git a/test/sdf_pose_tests.cpp b/test/pose_tests.cpp similarity index 100% rename from test/sdf_pose_tests.cpp rename to test/pose_tests.cpp From a697bfba9575447d2d622945c1f430865321c2d2 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 16:53:38 -0700 Subject: [PATCH 057/152] Shorter file name Signed-off-by: Shane Loretz --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9f51f548..42fd600e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,7 +88,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_pose_visual_in_frame" "pose_visual_in_frame") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) - ament_add_gtest(sdf_pose_tests "test/sdf_pose_tests.cpp") + ament_add_gtest(sdf_pose_tests "test/pose_tests.cpp") target_link_libraries(sdf_pose_tests sdformat_urdf) target_include_directories(sdf_pose_tests PRIVATE "${CMAKE_CURRENT_SOURCE_DIR}/test/include" From 57db264f2e1f85f2f384242c590d5d8336fecd54 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 17:02:19 -0700 Subject: [PATCH 058/152] Add graph_loop test Signed-off-by: Shane Loretz --- CMakeLists.txt | 7 +++++++ test/graph_tests.cpp | 32 ++++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 40 insertions(+) create mode 100644 test/graph_tests.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 42fd600e..d755c57b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + sdformat_test_files_get_model_sdf("path_to_sdf_graph_loop" "graph_loop") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision" "pose_collision") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision_in_frame" "pose_collision_in_frame") @@ -88,6 +89,12 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_pose_visual_in_frame" "pose_visual_in_frame") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) + ament_add_gtest(sdf_graph_tests "test/graph_tests.cpp") + target_link_libraries(sdf_graph_tests sdformat_urdf) + target_include_directories(sdf_graph_tests PRIVATE + "${CMAKE_CURRENT_SOURCE_DIR}/test/include" + "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_pose_tests "test/pose_tests.cpp") target_link_libraries(sdf_pose_tests sdformat_urdf) target_include_directories(sdf_pose_tests PRIVATE diff --git a/test/graph_tests.cpp b/test/graph_tests.cpp new file mode 100644 index 00000000..7d646828 --- /dev/null +++ b/test/graph_tests.cpp @@ -0,0 +1,32 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 +#include +#include +#include +#include + +#include "sdf_paths.hpp" +#include "test_tools.hpp" + +TEST(Graph, graph_loop) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GRAPH_LOOP), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 43d92ce3..44d47061 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,6 +15,7 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define PATH_TO_SDF_GRAPH_LOOP "@path_to_sdf_graph_loop@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" #define PATH_TO_SDF_POSE_COLLISION "@path_to_sdf_pose_collision@" #define PATH_TO_SDF_POSE_COLLISION_IN_FRAME "@path_to_sdf_pose_collision_in_frame@" From 06beeebd1253a17bbb627db8b5f472b8feb91842 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 17:04:11 -0700 Subject: [PATCH 059/152] Add graph_four_bar test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/graph_tests.cpp | 9 +++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index d755c57b..ea2608d8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + sdformat_test_files_get_model_sdf("path_to_sdf_graph_four_bar" "graph_four_bar") sdformat_test_files_get_model_sdf("path_to_sdf_graph_loop" "graph_loop") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision" "pose_collision") diff --git a/test/graph_tests.cpp b/test/graph_tests.cpp index 7d646828..de7ac4e1 100644 --- a/test/graph_tests.cpp +++ b/test/graph_tests.cpp @@ -30,3 +30,12 @@ TEST(Graph, graph_loop) EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } + +TEST(Graph, graph_four_bar) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GRAPH_FOUR_BAR), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 44d47061..ede075a2 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,6 +15,7 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define PATH_TO_SDF_GRAPH_FOUR_BAR "@path_to_sdf_graph_four_bar@" #define PATH_TO_SDF_GRAPH_LOOP "@path_to_sdf_graph_loop@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" #define PATH_TO_SDF_POSE_COLLISION "@path_to_sdf_pose_collision@" From 34700ae8ef62f520999e498f4a45df2e64fb5897 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 2 Oct 2020 17:05:44 -0700 Subject: [PATCH 060/152] Alphabetize Signed-off-by: Shane Loretz --- test/graph_tests.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/test/graph_tests.cpp b/test/graph_tests.cpp index de7ac4e1..2029ce1b 100644 --- a/test/graph_tests.cpp +++ b/test/graph_tests.cpp @@ -22,20 +22,20 @@ #include "sdf_paths.hpp" #include "test_tools.hpp" -TEST(Graph, graph_loop) +TEST(Graph, graph_four_bar) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(PATH_TO_SDF_GRAPH_LOOP), errors); + get_file(PATH_TO_SDF_GRAPH_FOUR_BAR), errors); EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } -TEST(Graph, graph_four_bar) +TEST(Graph, graph_loop) { sdf::Errors errors; urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( - get_file(PATH_TO_SDF_GRAPH_FOUR_BAR), errors); + get_file(PATH_TO_SDF_GRAPH_LOOP), errors); EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } From e8fe43bd5d4689fd245293551bd7b527de52621e Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 09:21:17 -0700 Subject: [PATCH 061/152] Refactor tree traversal code Fixes bug were tree's with non-canonical roots were not caught during conversion Shrink list of joints to check after checking them Use visited_links only to catch multiple roots and algorithm errors Get rid of trailing_ Signed-off-by: Shane Loretz Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 83 ++++++++++++++++++++++++++++--------------- 1 file changed, 55 insertions(+), 28 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 56bffd74..ad6b31a9 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -183,40 +183,33 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) } // Start with root link and resolve the poses one joint at a time depth-first - std::vector visited_links_; + std::vector visited_links; std::vector link_stack{sdf_canonical_link}; - while (!link_stack.empty()) { - const sdf::Link * sdf_parent_link = link_stack.back(); - urdf::LinkSharedPtr & urdf_parent_link = urdf_model->links_.at(sdf_parent_link->Name()); - link_stack.pop_back(); - - // Check if there is a kinematic loop - if (visited_links_.end() != - std::find(visited_links_.begin(), visited_links_.end(), sdf_parent_link)) - { + std::vector joints_to_visit(sdf_model.JointCount(), nullptr); + for (size_t j = 0; j < joints_to_visit.size(); ++j) { + joints_to_visit[j] = sdf_model.JointByIndex(j); + if (!joints_to_visit[j]) { errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Not a tree because link [" + sdf_parent_link->Name() + "] was visited twice"); + "Failed to get sdf joint"); return nullptr; } - visited_links_.emplace_back(sdf_parent_link); - - sdf::Errors pose_errors; - - // Look for joints attached to this link - for (uint64_t j = 0; j < sdf_model.JointCount(); ++j) { - const sdf::Joint * sdf_joint = sdf_model.JointByIndex(j); - - if (!sdf_joint) { - errors.emplace_back( - sdf::ErrorCode::STRING_READ, - "Failed to get sdf joint"); - return nullptr; - } + } + while (!link_stack.empty()) { + const sdf::Link * sdf_parent_link = link_stack.back(); + urdf::LinkSharedPtr & urdf_parent_link = urdf_model->links_.at(sdf_parent_link->Name()); + link_stack.pop_back(); + visited_links.emplace_back(sdf_parent_link); + auto joint_iter = joints_to_visit.begin(); + // Fix poses and check for tree structure issues + while (joint_iter != joints_to_visit.end()) { + const sdf::Joint * sdf_joint = *joint_iter; if (sdf_joint->ParentLinkName() == sdf_parent_link->Name()) { + // Visited parent link of this joint - don't look at it again + joint_iter = joints_to_visit.erase(joint_iter); + urdf::JointSharedPtr & urdf_joint = urdf_model->joints_.at(sdf_joint->Name()); - // Append to child joints urdf_parent_link->child_joints.push_back(urdf_joint); // SDFormat joint pose is relative to the child sdformat link @@ -228,7 +221,7 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) } ignition::math::Pose3d joint_pose; - pose_errors = sdf_joint->SemanticPose().Resolve(joint_pose, parent_frame_name); + sdf::Errors pose_errors = sdf_joint->SemanticPose().Resolve(joint_pose, parent_frame_name); if (!pose_errors.empty()) { errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( @@ -239,7 +232,6 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) } urdf_joint->parent_to_joint_origin_transform = convert_pose(joint_pose); - // get child link const std::string & child_link_name = urdf_joint->child_link_name; const sdf::Link * sdf_child_link = sdf_model.LinkByName(child_link_name); if (!sdf_child_link) { @@ -258,9 +250,44 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) // Explore this child link later link_stack.push_back(sdf_child_link); + } else if (sdf_joint->ChildLinkName() == sdf_parent_link->Name()) { + // Something is wrong here + if (sdf_parent_link == sdf_canonical_link) { + // The canonical link can't be a child of a joint + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Canonical link must not be a child of a joint [" + sdf_parent_link->Name() + "]"); + } else { + // This link must be a child of two joints - kinematic loop :( + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Link can only be a child of one joint [" + sdf_parent_link->Name() + "]"); + } + return nullptr; + } else { + // Not interested in this joint yet, look at the next one + ++joint_iter; } } } + if (visited_links.size() < sdf_model.LinkCount()) { + // Must be multiple roots + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Found multiple root links - must only have one link not a child of any joint"); + return nullptr; + } else if (visited_links.size() > sdf_model.LinkCount()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Algorithm error - visited more links than exist, please file a bug report"); + return nullptr; + } + if (!joints_to_visit.empty()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Algorithm error - did not visit all joints, please file a bug report"); + return nullptr; + } return urdf_model; } From 1b36817f15d02f66e22223a4a47ac55816c87897 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 09:23:36 -0700 Subject: [PATCH 062/152] Add graph_tree_non_canonical_root test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/graph_tests.cpp | 9 +++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index ea2608d8..a011c104 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -75,6 +75,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_graph_four_bar" "graph_four_bar") sdformat_test_files_get_model_sdf("path_to_sdf_graph_loop" "graph_loop") + sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree_non_canonical_root" "graph_tree_non_canonical_root") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision" "pose_collision") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision_in_frame" "pose_collision_in_frame") diff --git a/test/graph_tests.cpp b/test/graph_tests.cpp index 2029ce1b..11ac0da6 100644 --- a/test/graph_tests.cpp +++ b/test/graph_tests.cpp @@ -39,3 +39,12 @@ TEST(Graph, graph_loop) EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } + +TEST(Graph, graph_tree_non_canonical_root) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GRAPH_TREE_NON_CANONICAL_ROOT), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index ede075a2..3b88a807 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -17,6 +17,7 @@ #define PATH_TO_SDF_GRAPH_FOUR_BAR "@path_to_sdf_graph_four_bar@" #define PATH_TO_SDF_GRAPH_LOOP "@path_to_sdf_graph_loop@" +#define PATH_TO_SDF_GRAPH_TREE_NON_CANONICAL_ROOT "@path_to_sdf_graph_tree_non_canonical_root@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" #define PATH_TO_SDF_POSE_COLLISION "@path_to_sdf_pose_collision@" #define PATH_TO_SDF_POSE_COLLISION_IN_FRAME "@path_to_sdf_pose_collision_in_frame@" From 4d9416aba41190f748afca554a736a85af998d37 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 09:27:21 -0700 Subject: [PATCH 063/152] Transfrom -> transform Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index ad6b31a9..e8112937 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -226,7 +226,7 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get transfrom from joint [" + sdf_joint->Name() + + "Failed to get transform from joint [" + sdf_joint->Name() + "] to link [" + sdf_parent_link->Name() + "]"); return nullptr; } @@ -353,7 +353,7 @@ sdformat_urdf::convert_link( errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get transfrom from visual [" + sdf_visual->Name() + + "Failed to get transform from visual [" + sdf_visual->Name() + "] to link [" + sdf_link.Name() + "]"); return nullptr; } @@ -411,7 +411,7 @@ sdformat_urdf::convert_link( errors.insert(errors.end(), pose_errors.begin(), pose_errors.end()); errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get transfrom from collision [" + sdf_collision->Name() + + "Failed to get transform from collision [" + sdf_collision->Name() + "] to link [" + sdf_link.Name() + "]"); return nullptr; } @@ -485,7 +485,7 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) errors.insert(errors.end(), axis_errors.begin(), axis_errors.end()); errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get transfrom of joint axis in frame [" + sdf_axis->XyzExpressedIn() + + "Failed to get transform of joint axis in frame [" + sdf_axis->XyzExpressedIn() + "] to joint [" + sdf_joint.Name() + "]"); return nullptr; } From 1b64b3237c0f15dadd22263e1e7fa140a6d4be72 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 11:28:02 -0700 Subject: [PATCH 064/152] Different error when XML file has no model Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index e8112937..0901036b 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -66,6 +66,12 @@ sdformat_urdf::sdf_to_urdf(const sdf::Root & sdf_dom, sdf::Errors & errors) "SDFormat xml has a world; but only a single model is supported"); return nullptr; } + if (0u == sdf_dom.ModelCount()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "SDFormat xml has no models; need at least one"); + return nullptr; + } if (1u != sdf_dom.ModelCount()) { errors.emplace_back( sdf::ErrorCode::STRING_READ, From 0410a8423c487220a4e45e83a6bb0e70475918e0 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 11:28:32 -0700 Subject: [PATCH 065/152] urdf child link keeps weak reference to parent link Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 0901036b..46053ad1 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -251,6 +251,9 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) // child link is attached to parent joint urdf_child_link->parent_joint = urdf_joint; + // Child link keeps weak reference to parent link + urdf_child_link->setParent(urdf_parent_link); + // parent link has reference to child link urdf_parent_link->child_links.push_back(urdf_child_link); From ba62b98387f8d7749aa2adabb2be6dd970f3e70f Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 11:35:54 -0700 Subject: [PATCH 066/152] Add graph_tree test and EXPECT_NAMES util Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/graph_tests.cpp | 105 ++++++++++++++++++++++++++++++++++++ test/include/test_tools.hpp | 21 ++++++++ test/sdf_paths.hpp.in | 1 + 4 files changed, 128 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index a011c104..1b99a4e2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -75,6 +75,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_graph_four_bar" "graph_four_bar") sdformat_test_files_get_model_sdf("path_to_sdf_graph_loop" "graph_loop") + sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree" "graph_tree") sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree_non_canonical_root" "graph_tree_non_canonical_root") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision" "pose_collision") diff --git a/test/graph_tests.cpp b/test/graph_tests.cpp index 11ac0da6..3a7f7880 100644 --- a/test/graph_tests.cpp +++ b/test/graph_tests.cpp @@ -40,6 +40,111 @@ TEST(Graph, graph_loop) ASSERT_FALSE(model); } +TEST(Graph, graph_tree) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GRAPH_TREE), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("graph_tree", model->getName()); + + EXPECT_EQ(6u, model->links_.size()); + EXPECT_EQ(5u, model->joints_.size()); + + ASSERT_NE(nullptr, model->getRoot()); + EXPECT_EQ("link_1", model->getRoot()->name); + + { // link_1 + urdf::LinkConstSharedPtr link = model->getLink("link_1"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(nullptr, link->parent_joint); + EXPECT_EQ(nullptr, link->getParent()); + EXPECT_NAMES(link->child_joints, "joint_1", "joint_2"); + EXPECT_NAMES(link->child_links, "link_2", "link_3"); + } + + { // link_2 + urdf::LinkConstSharedPtr link = model->getLink("link_2"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(model->getJoint("joint_1"), link->parent_joint); + EXPECT_EQ(model->getLink("link_1"), link->getParent()); + EXPECT_NAMES(link->child_joints, "joint_3"); + EXPECT_NAMES(link->child_links, "link_4"); + } + + { // link_3 + urdf::LinkConstSharedPtr link = model->getLink("link_3"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(model->getJoint("joint_2"), link->parent_joint); + EXPECT_EQ(model->getLink("link_1"), link->getParent()); + EXPECT_NAMES(link->child_joints, "joint_4", "joint_5"); + EXPECT_NAMES(link->child_links, "link_5", "link_6"); + } + + { // link_4 + urdf::LinkConstSharedPtr link = model->getLink("link_4"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(model->getJoint("joint_3"), link->parent_joint); + EXPECT_EQ(model->getLink("link_2"), link->getParent()); + EXPECT_TRUE(link->child_joints.empty()); + EXPECT_TRUE(link->child_links.empty()); + } + + { // link_5 + urdf::LinkConstSharedPtr link = model->getLink("link_5"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(model->getJoint("joint_4"), link->parent_joint); + EXPECT_EQ(model->getLink("link_3"), link->getParent()); + EXPECT_TRUE(link->child_joints.empty()); + EXPECT_TRUE(link->child_links.empty()); + } + + { // link_6 + urdf::LinkConstSharedPtr link = model->getLink("link_6"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(model->getJoint("joint_5"), link->parent_joint); + EXPECT_EQ(model->getLink("link_3"), link->getParent()); + EXPECT_TRUE(link->child_joints.empty()); + EXPECT_TRUE(link->child_links.empty()); + } + + { // joint_1 + urdf::JointConstSharedPtr joint = model->getJoint("joint_1"); + ASSERT_NE(nullptr, joint); + EXPECT_EQ("link_1", joint->parent_link_name); + EXPECT_EQ("link_2", joint->child_link_name); + } + + { // joint_2 + urdf::JointConstSharedPtr joint = model->getJoint("joint_2"); + ASSERT_NE(nullptr, joint); + EXPECT_EQ("link_1", joint->parent_link_name); + EXPECT_EQ("link_3", joint->child_link_name); + } + + { // joint_3 + urdf::JointConstSharedPtr joint = model->getJoint("joint_3"); + ASSERT_NE(nullptr, joint); + EXPECT_EQ("link_2", joint->parent_link_name); + EXPECT_EQ("link_4", joint->child_link_name); + } + + { // joint_4 + urdf::JointConstSharedPtr joint = model->getJoint("joint_4"); + ASSERT_NE(nullptr, joint); + EXPECT_EQ("link_3", joint->parent_link_name); + EXPECT_EQ("link_5", joint->child_link_name); + } + + { // joint_5 + urdf::JointConstSharedPtr joint = model->getJoint("joint_5"); + ASSERT_NE(nullptr, joint); + EXPECT_EQ("link_3", joint->parent_link_name); + EXPECT_EQ("link_6", joint->child_link_name); + } +} + TEST(Graph, graph_tree_non_canonical_root) { sdf::Errors errors; diff --git a/test/include/test_tools.hpp b/test/include/test_tools.hpp index bec293d5..b4dcec71 100644 --- a/test/include/test_tools.hpp +++ b/test/include/test_tools.hpp @@ -21,6 +21,7 @@ #include #include #include +#include inline std::string @@ -45,6 +46,26 @@ get_file(const char * path) EXPECT_EQ(expected_ign, actual_ign); \ } while (false) +#define EXPECT_NAMES(child_ptr_list, ...) \ + do { \ + std::vector expected_names{__VA_ARGS__}; \ + ASSERT_EQ(expected_names.size(), child_ptr_list.size()); \ + for (const auto & child : child_ptr_list) { \ + bool name_is_expected = false; \ + auto expected_name_iter = expected_names.begin(); \ + while (expected_name_iter != expected_names.end()) { \ + if (* expected_name_iter == child->name) { \ + name_is_expected = true; \ + expected_names.erase(expected_name_iter); \ + break; \ + } \ + ++expected_name_iter; \ + } \ + ASSERT_TRUE(name_is_expected) << "Unexpected or duplicate name: " << child->name; \ + } \ + } while (false) + + std::ostream & operator<<(std::ostream & os, const sdf::Errors & errors) { for (const auto & error : errors) { diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 3b88a807..44acc369 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -17,6 +17,7 @@ #define PATH_TO_SDF_GRAPH_FOUR_BAR "@path_to_sdf_graph_four_bar@" #define PATH_TO_SDF_GRAPH_LOOP "@path_to_sdf_graph_loop@" +#define PATH_TO_SDF_GRAPH_TREE "@path_to_sdf_graph_tree@" #define PATH_TO_SDF_GRAPH_TREE_NON_CANONICAL_ROOT "@path_to_sdf_graph_tree_non_canonical_root@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" #define PATH_TO_SDF_POSE_COLLISION "@path_to_sdf_pose_collision@" From 27ceefcfb22fbb0cadd3479078912834ff1ae773 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 11:59:10 -0700 Subject: [PATCH 067/152] Add graph_chain test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/graph_tests.cpp | 57 +++++++++++++++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 59 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1b99a4e2..60bed002 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") sdformat_test_files_get_model_sdf("path_to_sdf_graph_four_bar" "graph_four_bar") sdformat_test_files_get_model_sdf("path_to_sdf_graph_loop" "graph_loop") sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree" "graph_tree") diff --git a/test/graph_tests.cpp b/test/graph_tests.cpp index 3a7f7880..a4bda744 100644 --- a/test/graph_tests.cpp +++ b/test/graph_tests.cpp @@ -22,6 +22,63 @@ #include "sdf_paths.hpp" #include "test_tools.hpp" +TEST(Graph, graph_chain) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GRAPH_CHAIN), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("graph_chain", model->getName()); + + EXPECT_EQ(3u, model->links_.size()); + EXPECT_EQ(2u, model->joints_.size()); + + ASSERT_NE(nullptr, model->getRoot()); + EXPECT_EQ("link_1", model->getRoot()->name); + + { // link_1 + urdf::LinkConstSharedPtr link = model->getLink("link_1"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(nullptr, link->parent_joint); + EXPECT_EQ(nullptr, link->getParent()); + EXPECT_NAMES(link->child_joints, "joint_1"); + EXPECT_NAMES(link->child_links, "link_2"); + } + + { // link_2 + urdf::LinkConstSharedPtr link = model->getLink("link_2"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(model->getJoint("joint_1"), link->parent_joint); + EXPECT_EQ(model->getLink("link_1"), link->getParent()); + EXPECT_NAMES(link->child_joints, "joint_2"); + EXPECT_NAMES(link->child_links, "link_3"); + } + + { // link_3 + urdf::LinkConstSharedPtr link = model->getLink("link_3"); + ASSERT_NE(nullptr, link); + EXPECT_EQ(model->getJoint("joint_2"), link->parent_joint); + EXPECT_EQ(model->getLink("link_2"), link->getParent()); + EXPECT_TRUE(link->child_joints.empty()); + EXPECT_TRUE(link->child_links.empty()); + } + + { // joint_1 + urdf::JointConstSharedPtr joint = model->getJoint("joint_1"); + ASSERT_NE(nullptr, joint); + EXPECT_EQ("link_1", joint->parent_link_name); + EXPECT_EQ("link_2", joint->child_link_name); + } + + { // joint_2 + urdf::JointConstSharedPtr joint = model->getJoint("joint_2"); + ASSERT_NE(nullptr, joint); + EXPECT_EQ("link_2", joint->parent_link_name); + EXPECT_EQ("link_3", joint->child_link_name); + } +} + TEST(Graph, graph_four_bar) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 44acc369..13531fd4 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,6 +15,7 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" #define PATH_TO_SDF_GRAPH_FOUR_BAR "@path_to_sdf_graph_four_bar@" #define PATH_TO_SDF_GRAPH_LOOP "@path_to_sdf_graph_loop@" #define PATH_TO_SDF_GRAPH_TREE "@path_to_sdf_graph_tree@" From f02e1ace817bf90f45b948dec85962206c0d1e75 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 12:01:38 -0700 Subject: [PATCH 068/152] Add graph_chain_non_canonical_root test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/graph_tests.cpp | 9 +++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 60bed002..03647ce2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -74,6 +74,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") + sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain_non_canonical_root" "graph_chain_non_canonical_root") sdformat_test_files_get_model_sdf("path_to_sdf_graph_four_bar" "graph_four_bar") sdformat_test_files_get_model_sdf("path_to_sdf_graph_loop" "graph_loop") sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree" "graph_tree") diff --git a/test/graph_tests.cpp b/test/graph_tests.cpp index a4bda744..c315ea69 100644 --- a/test/graph_tests.cpp +++ b/test/graph_tests.cpp @@ -79,6 +79,15 @@ TEST(Graph, graph_chain) } } +TEST(Graph, graph_chain_non_canonical_root) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GRAPH_CHAIN_NON_CANONICAL_ROOT), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} + TEST(Graph, graph_four_bar) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 13531fd4..7ae735dd 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -16,6 +16,7 @@ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" +#define PATH_TO_SDF_GRAPH_CHAIN_NON_CANONICAL_ROOT "@path_to_sdf_graph_chain_non_canonical_root@" #define PATH_TO_SDF_GRAPH_FOUR_BAR "@path_to_sdf_graph_four_bar@" #define PATH_TO_SDF_GRAPH_LOOP "@path_to_sdf_graph_loop@" #define PATH_TO_SDF_GRAPH_TREE "@path_to_sdf_graph_tree@" From bb10917db084e10b190a70c03cde65e0b4948cf1 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 14:41:48 -0700 Subject: [PATCH 069/152] Add geometry_plane test Signed-off-by: Shane Loretz --- CMakeLists.txt | 7 +++++++ test/geometry_tests.cpp | 32 ++++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 40 insertions(+) create mode 100644 test/geometry_tests.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 03647ce2..e3efddf6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain_non_canonical_root" "graph_chain_non_canonical_root") sdformat_test_files_get_model_sdf("path_to_sdf_graph_four_bar" "graph_four_bar") @@ -94,6 +95,12 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_pose_visual_in_frame" "pose_visual_in_frame") configure_file("test/sdf_paths.hpp.in" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes/sdf_paths.hpp" @ONLY) + ament_add_gtest(sdf_geometry_tests "test/geometry_tests.cpp") + target_link_libraries(sdf_geometry_tests sdformat_urdf) + target_include_directories(sdf_geometry_tests PRIVATE + "${CMAKE_CURRENT_SOURCE_DIR}/test/include" + "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_graph_tests "test/graph_tests.cpp") target_link_libraries(sdf_graph_tests sdformat_urdf) target_include_directories(sdf_graph_tests PRIVATE diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp new file mode 100644 index 00000000..1df517e3 --- /dev/null +++ b/test/geometry_tests.cpp @@ -0,0 +1,32 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 +#include +#include +#include +#include + +#include "sdf_paths.hpp" +#include "test_tools.hpp" + +TEST(Geometry, geometry_plane) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_PLANE), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 7ae735dd..bb5ddf5f 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,6 +15,7 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" #define PATH_TO_SDF_GRAPH_CHAIN_NON_CANONICAL_ROOT "@path_to_sdf_graph_chain_non_canonical_root@" #define PATH_TO_SDF_GRAPH_FOUR_BAR "@path_to_sdf_graph_four_bar@" From 312c3084b99691777f5b8790d86ea30768bb86c7 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 15:39:17 -0700 Subject: [PATCH 070/152] Add geometry_box test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/geometry_tests.cpp | 31 +++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 33 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index e3efddf6..35042fb0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ if(BUILD_TESTING) find_package(sdformat_test_files 0.1 REQUIRED) ament_lint_auto_find_test_dependencies() + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_box" "geometry_box") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain_non_canonical_root" "graph_chain_non_canonical_root") diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp index 1df517e3..003c5ccf 100644 --- a/test/geometry_tests.cpp +++ b/test/geometry_tests.cpp @@ -22,6 +22,37 @@ #include "sdf_paths.hpp" #include "test_tools.hpp" +TEST(Geometry, geometry_box) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_BOX), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("geometry_box", model->getName()); + + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + ASSERT_NE(nullptr, link->visual); + ASSERT_NE(nullptr, link->collision); + + ASSERT_EQ(urdf::Geometry::BOX, link->visual->geometry->type); + { + urdf::BoxConstSharedPtr box = std::dynamic_pointer_cast(link->visual->geometry); + EXPECT_DOUBLE_EQ(0.1, box->dim.x); + EXPECT_DOUBLE_EQ(0.2, box->dim.y); + EXPECT_DOUBLE_EQ(0.4, box->dim.z); + } + + ASSERT_EQ(urdf::Geometry::BOX, link->collision->geometry->type); + { + urdf::BoxConstSharedPtr box = std::dynamic_pointer_cast(link->collision->geometry); + EXPECT_DOUBLE_EQ(0.1, box->dim.x); + EXPECT_DOUBLE_EQ(0.2, box->dim.y); + EXPECT_DOUBLE_EQ(0.4, box->dim.z); + } +} + TEST(Geometry, geometry_plane) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index bb5ddf5f..7a241c4a 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -15,6 +15,7 @@ #ifndef SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ +#define PATH_TO_SDF_GEOMETRY_BOX "@path_to_sdf_geometry_box@" #define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" #define PATH_TO_SDF_GRAPH_CHAIN_NON_CANONICAL_ROOT "@path_to_sdf_graph_chain_non_canonical_root@" From d4e1611ccaa9cf5a6565a05f6c25d4529f0e8920 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 15:49:23 -0700 Subject: [PATCH 071/152] Add geometry_cylinder test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/geometry_tests.cpp | 31 +++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 33 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 35042fb0..5b03e55b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -74,6 +74,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() sdformat_test_files_get_model_sdf("path_to_sdf_geometry_box" "geometry_box") + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_cylinder" "geometry_cylinder") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain_non_canonical_root" "graph_chain_non_canonical_root") diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp index 003c5ccf..8d4c1d47 100644 --- a/test/geometry_tests.cpp +++ b/test/geometry_tests.cpp @@ -53,6 +53,37 @@ TEST(Geometry, geometry_box) } } +TEST(Geometry, geometry_cylinder) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_CYLINDER), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("geometry_cylinder", model->getName()); + + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + ASSERT_NE(nullptr, link->visual); + ASSERT_NE(nullptr, link->collision); + + ASSERT_EQ(urdf::Geometry::CYLINDER, link->visual->geometry->type); + { + urdf::CylinderConstSharedPtr cylinder = + std::dynamic_pointer_cast(link->visual->geometry); + EXPECT_DOUBLE_EQ(0.2, cylinder->length); + EXPECT_DOUBLE_EQ(0.125, cylinder->radius); + } + + ASSERT_EQ(urdf::Geometry::CYLINDER, link->collision->geometry->type); + { + urdf::CylinderConstSharedPtr cylinder = + std::dynamic_pointer_cast(link->collision->geometry); + EXPECT_DOUBLE_EQ(0.2, cylinder->length); + EXPECT_DOUBLE_EQ(0.125, cylinder->radius); + } +} + TEST(Geometry, geometry_plane) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 7a241c4a..17975ce6 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -16,6 +16,7 @@ #define SDFORMAT_URDF__TEST__SDF_PATHS_HPP_ #define PATH_TO_SDF_GEOMETRY_BOX "@path_to_sdf_geometry_box@" +#define PATH_TO_SDF_GEOMETRY_CYLINDER "@path_to_sdf_geometry_cylinder@" #define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" #define PATH_TO_SDF_GRAPH_CHAIN_NON_CANONICAL_ROOT "@path_to_sdf_graph_chain_non_canonical_root@" From 8afb5246e401c7f18f9fba4717986f616de031d3 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 15:49:36 -0700 Subject: [PATCH 072/152] Add geometry_sphere test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/geometry_tests.cpp | 29 +++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 31 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5b03e55b..5c7a90f0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -76,6 +76,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_geometry_box" "geometry_box") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_cylinder" "geometry_cylinder") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_sphere" "geometry_sphere") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain_non_canonical_root" "graph_chain_non_canonical_root") sdformat_test_files_get_model_sdf("path_to_sdf_graph_four_bar" "graph_four_bar") diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp index 8d4c1d47..5f36a48f 100644 --- a/test/geometry_tests.cpp +++ b/test/geometry_tests.cpp @@ -92,3 +92,32 @@ TEST(Geometry, geometry_plane) EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } + +TEST(Geometry, geometry_sphere) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_SPHERE), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("geometry_sphere", model->getName()); + + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + ASSERT_NE(nullptr, link->visual); + ASSERT_NE(nullptr, link->collision); + + ASSERT_EQ(urdf::Geometry::SPHERE, link->visual->geometry->type); + { + urdf::SphereConstSharedPtr sphere = + std::dynamic_pointer_cast(link->visual->geometry); + EXPECT_DOUBLE_EQ(0.125, sphere->radius); + } + + ASSERT_EQ(urdf::Geometry::SPHERE, link->collision->geometry->type); + { + urdf::SphereConstSharedPtr sphere = + std::dynamic_pointer_cast(link->collision->geometry); + EXPECT_DOUBLE_EQ(0.125, sphere->radius); + } +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 17975ce6..9a9031af 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -18,6 +18,7 @@ #define PATH_TO_SDF_GEOMETRY_BOX "@path_to_sdf_geometry_box@" #define PATH_TO_SDF_GEOMETRY_CYLINDER "@path_to_sdf_geometry_cylinder@" #define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" +#define PATH_TO_SDF_GEOMETRY_SPHERE "@path_to_sdf_geometry_sphere@" #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" #define PATH_TO_SDF_GRAPH_CHAIN_NON_CANONICAL_ROOT "@path_to_sdf_graph_chain_non_canonical_root@" #define PATH_TO_SDF_GRAPH_FOUR_BAR "@path_to_sdf_graph_four_bar@" From aad25df9f58bf74341a02f32488a6afc94dc1d51 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 15:59:54 -0700 Subject: [PATCH 073/152] Add geometry_heightmap test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/geometry_tests.cpp | 9 +++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5c7a90f0..17039a30 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -75,6 +75,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_geometry_box" "geometry_box") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_cylinder" "geometry_cylinder") + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_heightmap" "geometry_heightmap") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_sphere" "geometry_sphere") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp index 5f36a48f..4d732468 100644 --- a/test/geometry_tests.cpp +++ b/test/geometry_tests.cpp @@ -84,6 +84,15 @@ TEST(Geometry, geometry_cylinder) } } +TEST(Geometry, geometry_heightmap) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_HEIGHTMAP), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} + TEST(Geometry, geometry_plane) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 9a9031af..4ca397a1 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -17,6 +17,7 @@ #define PATH_TO_SDF_GEOMETRY_BOX "@path_to_sdf_geometry_box@" #define PATH_TO_SDF_GEOMETRY_CYLINDER "@path_to_sdf_geometry_cylinder@" +#define PATH_TO_SDF_GEOMETRY_HEIGHTMAP "@path_to_sdf_geometry_heightmap@" #define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" #define PATH_TO_SDF_GEOMETRY_SPHERE "@path_to_sdf_geometry_sphere@" #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" From 911a6fcbbfe4d45a408a0c2ac7d38ded07476e52 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 16:19:30 -0700 Subject: [PATCH 074/152] Add geometry_collada test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/geometry_tests.cpp | 29 +++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 31 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 17039a30..ef1f8b70 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -76,6 +76,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_geometry_box" "geometry_box") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_cylinder" "geometry_cylinder") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_heightmap" "geometry_heightmap") + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_collada" "geometry_mesh_collada") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_sphere" "geometry_sphere") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp index 4d732468..75a8fc2e 100644 --- a/test/geometry_tests.cpp +++ b/test/geometry_tests.cpp @@ -93,6 +93,35 @@ TEST(Geometry, geometry_heightmap) ASSERT_FALSE(model); } +TEST(Geometry, geometry_mesh_collada) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_MESH_COLLADA), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("geometry_mesh_collada", model->getName()); + + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + ASSERT_NE(nullptr, link->visual); + ASSERT_NE(nullptr, link->collision); + + ASSERT_EQ(urdf::Geometry::MESH, link->visual->geometry->type); + { + urdf::MeshConstSharedPtr mesh = + std::dynamic_pointer_cast(link->visual->geometry); + EXPECT_EQ("model://geometry_mesh_collada/torus.dae", mesh->filename); + } + + ASSERT_EQ(urdf::Geometry::MESH, link->collision->geometry->type); + { + urdf::MeshConstSharedPtr mesh = + std::dynamic_pointer_cast(link->collision->geometry); + EXPECT_EQ("model://geometry_mesh_collada/torus.dae", mesh->filename); + } +} + TEST(Geometry, geometry_plane) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 4ca397a1..e0401ecf 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -18,6 +18,7 @@ #define PATH_TO_SDF_GEOMETRY_BOX "@path_to_sdf_geometry_box@" #define PATH_TO_SDF_GEOMETRY_CYLINDER "@path_to_sdf_geometry_cylinder@" #define PATH_TO_SDF_GEOMETRY_HEIGHTMAP "@path_to_sdf_geometry_heightmap@" +#define PATH_TO_SDF_GEOMETRY_MESH_COLLADA "@path_to_sdf_geometry_mesh_collada@" #define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" #define PATH_TO_SDF_GEOMETRY_SPHERE "@path_to_sdf_geometry_sphere@" #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" From aa8d277e037e1b22bdc3ee38f7ab95384141a114 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 16:21:22 -0700 Subject: [PATCH 075/152] Add geometry_obj test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/geometry_tests.cpp | 29 +++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 31 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index ef1f8b70..d4595804 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -77,6 +77,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_geometry_cylinder" "geometry_cylinder") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_heightmap" "geometry_heightmap") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_collada" "geometry_mesh_collada") + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_obj" "geometry_mesh_obj") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_sphere" "geometry_sphere") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp index 75a8fc2e..f27ba9fd 100644 --- a/test/geometry_tests.cpp +++ b/test/geometry_tests.cpp @@ -122,6 +122,35 @@ TEST(Geometry, geometry_mesh_collada) } } +TEST(Geometry, geometry_mesh_obj) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_MESH_OBJ), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("geometry_mesh_obj", model->getName()); + + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + ASSERT_NE(nullptr, link->visual); + ASSERT_NE(nullptr, link->collision); + + ASSERT_EQ(urdf::Geometry::MESH, link->visual->geometry->type); + { + urdf::MeshConstSharedPtr mesh = + std::dynamic_pointer_cast(link->visual->geometry); + EXPECT_EQ("model://geometry_mesh_obj/torus.obj", mesh->filename); + } + + ASSERT_EQ(urdf::Geometry::MESH, link->collision->geometry->type); + { + urdf::MeshConstSharedPtr mesh = + std::dynamic_pointer_cast(link->collision->geometry); + EXPECT_EQ("model://geometry_mesh_obj/torus.obj", mesh->filename); + } +} + TEST(Geometry, geometry_plane) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index e0401ecf..88bc927c 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -19,6 +19,7 @@ #define PATH_TO_SDF_GEOMETRY_CYLINDER "@path_to_sdf_geometry_cylinder@" #define PATH_TO_SDF_GEOMETRY_HEIGHTMAP "@path_to_sdf_geometry_heightmap@" #define PATH_TO_SDF_GEOMETRY_MESH_COLLADA "@path_to_sdf_geometry_mesh_collada@" +#define PATH_TO_SDF_GEOMETRY_MESH_OBJ "@path_to_sdf_geometry_mesh_obj@" #define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" #define PATH_TO_SDF_GEOMETRY_SPHERE "@path_to_sdf_geometry_sphere@" #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" From d32e4fe944412476986ce5de18b394a2b1a0c944 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 16:23:00 -0700 Subject: [PATCH 076/152] Add geometry_stl test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/geometry_tests.cpp | 29 +++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 31 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index d4595804..018f1296 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -78,6 +78,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_geometry_heightmap" "geometry_heightmap") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_collada" "geometry_mesh_collada") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_obj" "geometry_mesh_obj") + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_stl" "geometry_mesh_stl") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_sphere" "geometry_sphere") sdformat_test_files_get_model_sdf("path_to_sdf_graph_chain" "graph_chain") diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp index f27ba9fd..e5cc28c6 100644 --- a/test/geometry_tests.cpp +++ b/test/geometry_tests.cpp @@ -151,6 +151,35 @@ TEST(Geometry, geometry_mesh_obj) } } +TEST(Geometry, geometry_mesh_stl) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_MESH_STL), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("geometry_mesh_stl", model->getName()); + + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + ASSERT_NE(nullptr, link->visual); + ASSERT_NE(nullptr, link->collision); + + ASSERT_EQ(urdf::Geometry::MESH, link->visual->geometry->type); + { + urdf::MeshConstSharedPtr mesh = + std::dynamic_pointer_cast(link->visual->geometry); + EXPECT_EQ("model://geometry_mesh_stl/torus.stl", mesh->filename); + } + + ASSERT_EQ(urdf::Geometry::MESH, link->collision->geometry->type); + { + urdf::MeshConstSharedPtr mesh = + std::dynamic_pointer_cast(link->collision->geometry); + EXPECT_EQ("model://geometry_mesh_stl/torus.stl", mesh->filename); + } +} + TEST(Geometry, geometry_plane) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 88bc927c..8cd946bc 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -20,6 +20,7 @@ #define PATH_TO_SDF_GEOMETRY_HEIGHTMAP "@path_to_sdf_geometry_heightmap@" #define PATH_TO_SDF_GEOMETRY_MESH_COLLADA "@path_to_sdf_geometry_mesh_collada@" #define PATH_TO_SDF_GEOMETRY_MESH_OBJ "@path_to_sdf_geometry_mesh_obj@" +#define PATH_TO_SDF_GEOMETRY_MESH_STL "@path_to_sdf_geometry_mesh_stl@" #define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" #define PATH_TO_SDF_GEOMETRY_SPHERE "@path_to_sdf_geometry_sphere@" #define PATH_TO_SDF_GRAPH_CHAIN "@path_to_sdf_graph_chain@" From d9a6adc1c445d7905b52eb463aa3575cab621946 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 5 Oct 2020 16:31:39 -0700 Subject: [PATCH 077/152] Add geometry_mesh_scaled test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/geometry_tests.cpp | 35 +++++++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 37 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 018f1296..f2ddda78 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -78,6 +78,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_geometry_heightmap" "geometry_heightmap") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_collada" "geometry_mesh_collada") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_obj" "geometry_mesh_obj") + sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_scaled" "geometry_mesh_scaled") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_mesh_stl" "geometry_mesh_stl") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_plane" "geometry_plane") sdformat_test_files_get_model_sdf("path_to_sdf_geometry_sphere" "geometry_sphere") diff --git a/test/geometry_tests.cpp b/test/geometry_tests.cpp index e5cc28c6..0c641243 100644 --- a/test/geometry_tests.cpp +++ b/test/geometry_tests.cpp @@ -151,6 +151,41 @@ TEST(Geometry, geometry_mesh_obj) } } +TEST(Geometry, geometry_mesh_scaled) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_GEOMETRY_MESH_SCALED), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("geometry_mesh_scaled", model->getName()); + + urdf::LinkConstSharedPtr link = model->getRoot(); + ASSERT_NE(nullptr, link); + ASSERT_NE(nullptr, link->visual); + ASSERT_NE(nullptr, link->collision); + + ASSERT_EQ(urdf::Geometry::MESH, link->visual->geometry->type); + { + urdf::MeshConstSharedPtr mesh = + std::dynamic_pointer_cast(link->visual->geometry); + EXPECT_EQ("model://geometry_mesh_scaled/torus.stl", mesh->filename); + EXPECT_DOUBLE_EQ(0.1, mesh->scale.x); + EXPECT_DOUBLE_EQ(0.2, mesh->scale.y); + EXPECT_DOUBLE_EQ(0.4, mesh->scale.z); + } + + ASSERT_EQ(urdf::Geometry::MESH, link->collision->geometry->type); + { + urdf::MeshConstSharedPtr mesh = + std::dynamic_pointer_cast(link->collision->geometry); + EXPECT_EQ("model://geometry_mesh_scaled/torus.stl", mesh->filename); + EXPECT_DOUBLE_EQ(0.1, mesh->scale.x); + EXPECT_DOUBLE_EQ(0.2, mesh->scale.y); + EXPECT_DOUBLE_EQ(0.4, mesh->scale.z); + } +} + TEST(Geometry, geometry_mesh_stl) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 8cd946bc..7c1854be 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -20,6 +20,7 @@ #define PATH_TO_SDF_GEOMETRY_HEIGHTMAP "@path_to_sdf_geometry_heightmap@" #define PATH_TO_SDF_GEOMETRY_MESH_COLLADA "@path_to_sdf_geometry_mesh_collada@" #define PATH_TO_SDF_GEOMETRY_MESH_OBJ "@path_to_sdf_geometry_mesh_obj@" +#define PATH_TO_SDF_GEOMETRY_MESH_SCALED "@path_to_sdf_geometry_mesh_scaled@" #define PATH_TO_SDF_GEOMETRY_MESH_STL "@path_to_sdf_geometry_mesh_stl@" #define PATH_TO_SDF_GEOMETRY_PLANE "@path_to_sdf_geometry_plane@" #define PATH_TO_SDF_GEOMETRY_SPHERE "@path_to_sdf_geometry_sphere@" From 621d8b6b6dd1a1e3d288713e843387349ec35152 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 09:53:12 -0700 Subject: [PATCH 078/152] Add tests for zero and two models Signed-off-by: Shane Loretz --- CMakeLists.txt | 8 ++++++++ test/model_tests.cpp | 41 +++++++++++++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 2 ++ 3 files changed, 51 insertions(+) create mode 100644 test/model_tests.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index f2ddda78..3a6a9c80 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,6 +88,8 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_graph_loop" "graph_loop") sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree" "graph_tree") sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree_non_canonical_root" "graph_tree_non_canonical_root") + sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") + sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision" "pose_collision") sdformat_test_files_get_model_sdf("path_to_sdf_pose_collision_in_frame" "pose_collision_in_frame") @@ -115,6 +117,12 @@ if(BUILD_TESTING) "${CMAKE_CURRENT_SOURCE_DIR}/test/include" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_model_tests "test/model_tests.cpp") + target_link_libraries(sdf_model_tests sdformat_urdf) + target_include_directories(sdf_model_tests PRIVATE + "${CMAKE_CURRENT_SOURCE_DIR}/test/include" + "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_pose_tests "test/pose_tests.cpp") target_link_libraries(sdf_pose_tests sdformat_urdf) target_include_directories(sdf_pose_tests PRIVATE diff --git a/test/model_tests.cpp b/test/model_tests.cpp new file mode 100644 index 00000000..6ccec8ac --- /dev/null +++ b/test/model_tests.cpp @@ -0,0 +1,41 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 +#include +#include +#include +#include + +#include "sdf_paths.hpp" +#include "test_tools.hpp" + +TEST(Model, model_two_models) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_MODEL_TWO_MODELS), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} + +TEST(Model, model_zero_models) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_MODEL_ZERO_MODELS), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 7c1854be..3e5f070a 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -30,6 +30,8 @@ #define PATH_TO_SDF_GRAPH_LOOP "@path_to_sdf_graph_loop@" #define PATH_TO_SDF_GRAPH_TREE "@path_to_sdf_graph_tree@" #define PATH_TO_SDF_GRAPH_TREE_NON_CANONICAL_ROOT "@path_to_sdf_graph_tree_non_canonical_root@" +#define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" +#define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" #define PATH_TO_SDF_POSE_COLLISION "@path_to_sdf_pose_collision@" #define PATH_TO_SDF_POSE_COLLISION_IN_FRAME "@path_to_sdf_pose_collision_in_frame@" From 3743f8f398c4b6f3d27af57204bb427ba054a0f5 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 12:16:11 -0700 Subject: [PATCH 079/152] Add joint_ball test Signed-off-by: Shane Loretz --- CMakeLists.txt | 7 +++++++ test/joint_tests.cpp | 32 ++++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 40 insertions(+) create mode 100644 test/joint_tests.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 3a6a9c80..7f9e561d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,6 +88,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_graph_loop" "graph_loop") sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree" "graph_tree") sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree_non_canonical_root" "graph_tree_non_canonical_root") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_ball" "joint_ball") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") @@ -117,6 +118,12 @@ if(BUILD_TESTING) "${CMAKE_CURRENT_SOURCE_DIR}/test/include" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_joint_tests "test/joint_tests.cpp") + target_link_libraries(sdf_joint_tests sdformat_urdf) + target_include_directories(sdf_joint_tests PRIVATE + "${CMAKE_CURRENT_SOURCE_DIR}/test/include" + "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_model_tests "test/model_tests.cpp") target_link_libraries(sdf_model_tests sdformat_urdf) target_include_directories(sdf_model_tests PRIVATE diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp new file mode 100644 index 00000000..003051bc --- /dev/null +++ b/test/joint_tests.cpp @@ -0,0 +1,32 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 +#include +#include +#include +#include + +#include "sdf_paths.hpp" +#include "test_tools.hpp" + +TEST(Joint, joint_ball) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_BALL), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 3e5f070a..5dd5f7ce 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -30,6 +30,7 @@ #define PATH_TO_SDF_GRAPH_LOOP "@path_to_sdf_graph_loop@" #define PATH_TO_SDF_GRAPH_TREE "@path_to_sdf_graph_tree@" #define PATH_TO_SDF_GRAPH_TREE_NON_CANONICAL_ROOT "@path_to_sdf_graph_tree_non_canonical_root@" +#define PATH_TO_SDF_JOINT_BALL "@path_to_sdf_joint_ball@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From ce650684296f14da2e4511195b998d1ce6529626 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 16:23:34 -0700 Subject: [PATCH 080/152] Get rid of num_axes variable Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 46053ad1..1d22a0b2 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -451,24 +451,18 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) urdf_joint->name = sdf_joint.Name(); - size_t num_axes = 0; - switch (sdf_joint.Type()) { case sdf::JointType::CONTINUOUS: urdf_joint->type = urdf::Joint::CONTINUOUS; - num_axes = 1; break; case sdf::JointType::REVOLUTE: urdf_joint->type = urdf::Joint::REVOLUTE; - num_axes = 1; break; case sdf::JointType::FIXED: urdf_joint->type = urdf::Joint::FIXED; - num_axes = 0; break; case sdf::JointType::PRISMATIC: urdf_joint->type = urdf::Joint::PRISMATIC; - num_axes = 1; break; case sdf::JointType::INVALID: // Unsupported: fall through to default case sdf::JointType::BALL: // | @@ -483,8 +477,8 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) return nullptr; } - // Supported joints have at most one axis - if (1 == num_axes) { + // Add axis info for non-fixed joints + if (urdf::Joint::FIXED != urdf_joint->type) { const sdf::JointAxis * sdf_axis = sdf_joint.Axis(0); // URDF expects axis to be expressed in the joint frame From c8e033ec5c7474b3f2eef684a78acf16b69dd7c7 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 16:38:52 -0700 Subject: [PATCH 081/152] Add damping and friction info to joints Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 1d22a0b2..a7c942fa 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -477,8 +477,8 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) return nullptr; } - // Add axis info for non-fixed joints if (urdf::Joint::FIXED != urdf_joint->type) { + // Add axis info for non-fixed joints const sdf::JointAxis * sdf_axis = sdf_joint.Axis(0); // URDF expects axis to be expressed in the joint frame @@ -492,12 +492,17 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) "] to joint [" + sdf_joint.Name() + "]"); return nullptr; } - urdf_joint->axis.x = axis_xyz.X(); urdf_joint->axis.y = axis_xyz.Y(); urdf_joint->axis.z = axis_xyz.Z(); + + // Add dynamics info for non-fixed joints + urdf_joint->dynamics = std::make_shared(); + urdf_joint->dynamics->damping = sdf_axis->Damping(); + urdf_joint->dynamics->friction = sdf_axis->Friction(); } + urdf_joint->child_link_name = sdf_joint.ChildLinkName(); urdf_joint->parent_link_name = sdf_joint.ParentLinkName(); From 9a48ea205387c4f1dd9608f05e4e28f1f0ef13b3 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 16:39:25 -0700 Subject: [PATCH 082/152] Add joint_continuous test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 22 ++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 24 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7f9e561d..9dae4794 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -89,6 +89,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree" "graph_tree") sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree_non_canonical_root" "graph_tree_non_canonical_root") sdformat_test_files_get_model_sdf("path_to_sdf_joint_ball" "joint_ball") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_continuous" "joint_continuous") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index 003051bc..847673bb 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -30,3 +30,25 @@ TEST(Joint, joint_ball) EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } + +TEST(Joint, joint_continuous) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_CONTINUOUS), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("joint_continuous", model->getName()); + + urdf::JointConstSharedPtr joint = model->getJoint("joint_continuous"); + + EXPECT_EQ("joint_continuous", joint->name); + EXPECT_EQ(urdf::Joint::CONTINUOUS, joint->type); + ASSERT_NE(nullptr, joint->dynamics); + EXPECT_DOUBLE_EQ(0, joint->dynamics->damping); + EXPECT_DOUBLE_EQ(0, joint->dynamics->friction); + ASSERT_EQ(nullptr, joint->limits); + ASSERT_EQ(nullptr, joint->safety); + ASSERT_EQ(nullptr, joint->calibration); + ASSERT_EQ(nullptr, joint->mimic); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 5dd5f7ce..eb353629 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -31,6 +31,7 @@ #define PATH_TO_SDF_GRAPH_TREE "@path_to_sdf_graph_tree@" #define PATH_TO_SDF_GRAPH_TREE_NON_CANONICAL_ROOT "@path_to_sdf_graph_tree_non_canonical_root@" #define PATH_TO_SDF_JOINT_BALL "@path_to_sdf_joint_ball@" +#define PATH_TO_SDF_JOINT_CONTINUOUS "@path_to_sdf_joint_continuous@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From dc21ca8f12032c588024627244c066f57d865a8a Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 16:42:07 -0700 Subject: [PATCH 083/152] Add joint_fixed test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 20 ++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 22 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9dae4794..a3779205 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -90,6 +90,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_graph_tree_non_canonical_root" "graph_tree_non_canonical_root") sdformat_test_files_get_model_sdf("path_to_sdf_joint_ball" "joint_ball") sdformat_test_files_get_model_sdf("path_to_sdf_joint_continuous" "joint_continuous") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_fixed" "joint_fixed") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index 847673bb..816b63ee 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -52,3 +52,23 @@ TEST(Joint, joint_continuous) ASSERT_EQ(nullptr, joint->calibration); ASSERT_EQ(nullptr, joint->mimic); } + +TEST(Joint, joint_fixed) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_FIXED), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("joint_fixed", model->getName()); + + urdf::JointConstSharedPtr joint = model->getJoint("joint_fixed"); + + EXPECT_EQ("joint_fixed", joint->name); + EXPECT_EQ(urdf::Joint::FIXED, joint->type); + ASSERT_EQ(nullptr, joint->dynamics); + ASSERT_EQ(nullptr, joint->limits); + ASSERT_EQ(nullptr, joint->safety); + ASSERT_EQ(nullptr, joint->calibration); + ASSERT_EQ(nullptr, joint->mimic); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index eb353629..429b1191 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -32,6 +32,7 @@ #define PATH_TO_SDF_GRAPH_TREE_NON_CANONICAL_ROOT "@path_to_sdf_graph_tree_non_canonical_root@" #define PATH_TO_SDF_JOINT_BALL "@path_to_sdf_joint_ball@" #define PATH_TO_SDF_JOINT_CONTINUOUS "@path_to_sdf_joint_continuous@" +#define PATH_TO_SDF_JOINT_FIXED "@path_to_sdf_joint_fixed@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 4f7de1a70aa7a1762a131a61ffaeb78d31c42139 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 17:04:23 -0700 Subject: [PATCH 084/152] Add joint limits info Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index a7c942fa..cab1c6f4 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -500,6 +500,15 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) urdf_joint->dynamics = std::make_shared(); urdf_joint->dynamics->damping = sdf_axis->Damping(); urdf_joint->dynamics->friction = sdf_axis->Friction(); + + // Add limits info for non-fixed non-continuous joints + if (urdf::Joint::CONTINUOUS != urdf_joint->type) { + urdf_joint->limits = std::make_shared(); + urdf_joint->limits->lower = sdf_axis->Lower(); + urdf_joint->limits->upper = sdf_axis->Upper(); + urdf_joint->limits->effort = sdf_axis->Effort(); + urdf_joint->limits->velocity = sdf_axis->MaxVelocity(); + } } From d6d122addaed5f52c0e0d9b6aa36b69e789e47a4 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 17:04:45 -0700 Subject: [PATCH 085/152] Add joint_prismatic test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 26 ++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 28 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index a3779205..06929b25 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -91,6 +91,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_ball" "joint_ball") sdformat_test_files_get_model_sdf("path_to_sdf_joint_continuous" "joint_continuous") sdformat_test_files_get_model_sdf("path_to_sdf_joint_fixed" "joint_fixed") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_prismatic" "joint_prismatic") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index 816b63ee..ef09a714 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -72,3 +72,29 @@ TEST(Joint, joint_fixed) ASSERT_EQ(nullptr, joint->calibration); ASSERT_EQ(nullptr, joint->mimic); } + +TEST(Joint, joint_prismatic) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_PRISMATIC), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("joint_prismatic", model->getName()); + + urdf::JointConstSharedPtr joint = model->getJoint("joint_prismatic"); + + EXPECT_EQ("joint_prismatic", joint->name); + EXPECT_EQ(urdf::Joint::PRISMATIC, joint->type); + ASSERT_NE(nullptr, joint->dynamics); + EXPECT_DOUBLE_EQ(0, joint->dynamics->damping); + EXPECT_DOUBLE_EQ(0, joint->dynamics->friction); + ASSERT_NE(nullptr, joint->limits); + EXPECT_DOUBLE_EQ(-0.2, joint->limits->lower); + EXPECT_DOUBLE_EQ(0.2, joint->limits->upper); + EXPECT_DOUBLE_EQ(-1, joint->limits->effort); // SDFormat default + EXPECT_DOUBLE_EQ(-1, joint->limits->velocity); // SDFormat default + ASSERT_EQ(nullptr, joint->safety); + ASSERT_EQ(nullptr, joint->calibration); + ASSERT_EQ(nullptr, joint->mimic); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 429b1191..d1d7dbca 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -33,6 +33,7 @@ #define PATH_TO_SDF_JOINT_BALL "@path_to_sdf_joint_ball@" #define PATH_TO_SDF_JOINT_CONTINUOUS "@path_to_sdf_joint_continuous@" #define PATH_TO_SDF_JOINT_FIXED "@path_to_sdf_joint_fixed@" +#define PATH_TO_SDF_JOINT_PRISMATIC "@path_to_sdf_joint_prismatic@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From da03bc6713bdeededaf29466bbdcf0f07c938599 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 17:15:13 -0700 Subject: [PATCH 086/152] Add axis expectations Signed-off-by: Shane Loretz --- test/joint_tests.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index ef09a714..483f11b7 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -44,6 +44,9 @@ TEST(Joint, joint_continuous) EXPECT_EQ("joint_continuous", joint->name); EXPECT_EQ(urdf::Joint::CONTINUOUS, joint->type); + EXPECT_DOUBLE_EQ(1, joint->axis.x); + EXPECT_DOUBLE_EQ(0, joint->axis.y); + EXPECT_DOUBLE_EQ(0, joint->axis.z); ASSERT_NE(nullptr, joint->dynamics); EXPECT_DOUBLE_EQ(0, joint->dynamics->damping); EXPECT_DOUBLE_EQ(0, joint->dynamics->friction); @@ -86,6 +89,9 @@ TEST(Joint, joint_prismatic) EXPECT_EQ("joint_prismatic", joint->name); EXPECT_EQ(urdf::Joint::PRISMATIC, joint->type); + EXPECT_DOUBLE_EQ(0, joint->axis.x); + EXPECT_DOUBLE_EQ(1, joint->axis.y); + EXPECT_DOUBLE_EQ(0, joint->axis.z); ASSERT_NE(nullptr, joint->dynamics); EXPECT_DOUBLE_EQ(0, joint->dynamics->damping); EXPECT_DOUBLE_EQ(0, joint->dynamics->friction); From f48200ee2f8a643eb720718797c4ec6a55ad2d9c Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 6 Oct 2020 17:20:27 -0700 Subject: [PATCH 087/152] Add joint_revolute test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 26 ++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 28 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 06929b25..e6f6e681 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -92,6 +92,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_continuous" "joint_continuous") sdformat_test_files_get_model_sdf("path_to_sdf_joint_fixed" "joint_fixed") sdformat_test_files_get_model_sdf("path_to_sdf_joint_prismatic" "joint_prismatic") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute" "joint_revolute") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index 483f11b7..d7bfc9f9 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -104,3 +104,29 @@ TEST(Joint, joint_prismatic) ASSERT_EQ(nullptr, joint->calibration); ASSERT_EQ(nullptr, joint->mimic); } + +TEST(Joint, joint_revolute) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_REVOLUTE), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("joint_revolute", model->getName()); + + urdf::JointConstSharedPtr joint = model->getJoint("joint_revolute"); + + EXPECT_EQ("joint_revolute", joint->name); + EXPECT_EQ(urdf::Joint::REVOLUTE, joint->type); + ASSERT_NE(nullptr, joint->dynamics); + EXPECT_DOUBLE_EQ(0, joint->dynamics->damping); + EXPECT_DOUBLE_EQ(0, joint->dynamics->friction); + ASSERT_NE(nullptr, joint->limits); + EXPECT_DOUBLE_EQ(-1.5, joint->limits->lower); + EXPECT_DOUBLE_EQ(1.5, joint->limits->upper); + EXPECT_DOUBLE_EQ(-1, joint->limits->effort); // SDFormat default + EXPECT_DOUBLE_EQ(-1, joint->limits->velocity); // SDFormat default + ASSERT_EQ(nullptr, joint->safety); + ASSERT_EQ(nullptr, joint->calibration); + ASSERT_EQ(nullptr, joint->mimic); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index d1d7dbca..d108d8a4 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -34,6 +34,7 @@ #define PATH_TO_SDF_JOINT_CONTINUOUS "@path_to_sdf_joint_continuous@" #define PATH_TO_SDF_JOINT_FIXED "@path_to_sdf_joint_fixed@" #define PATH_TO_SDF_JOINT_PRISMATIC "@path_to_sdf_joint_prismatic@" +#define PATH_TO_SDF_JOINT_REVOLUTE "@path_to_sdf_joint_revolute@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 3dbbe6d69da5a7e22e75b3d4d54a39600ea81f4f Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 7 Oct 2020 09:48:09 -0700 Subject: [PATCH 088/152] Add joint_revolute2 test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 9 +++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index e6f6e681..516d2ceb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -93,6 +93,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_fixed" "joint_fixed") sdformat_test_files_get_model_sdf("path_to_sdf_joint_prismatic" "joint_prismatic") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute" "joint_revolute") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute2" "joint_revolute2") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index d7bfc9f9..bcb92120 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -130,3 +130,12 @@ TEST(Joint, joint_revolute) ASSERT_EQ(nullptr, joint->calibration); ASSERT_EQ(nullptr, joint->mimic); } + +TEST(Joint, joint_revolute2) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_REVOLUTE2), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index d108d8a4..a3bd0c76 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -35,6 +35,7 @@ #define PATH_TO_SDF_JOINT_FIXED "@path_to_sdf_joint_fixed@" #define PATH_TO_SDF_JOINT_PRISMATIC "@path_to_sdf_joint_prismatic@" #define PATH_TO_SDF_JOINT_REVOLUTE "@path_to_sdf_joint_revolute@" +#define PATH_TO_SDF_JOINT_REVOLUTE2 "@path_to_sdf_joint_revolute2@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 95a2d0481ad8453e6e87c73c6cb25348033d59c4 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 7 Oct 2020 09:54:37 -0700 Subject: [PATCH 089/152] Add joint_screw test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 9 +++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 516d2ceb..bbc920bc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -94,6 +94,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_prismatic" "joint_prismatic") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute" "joint_revolute") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute2" "joint_revolute2") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index bcb92120..962a3df1 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -139,3 +139,12 @@ TEST(Joint, joint_revolute2) EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } + +TEST(Joint, joint_screw) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_SCREW), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index a3bd0c76..b3c5235b 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -36,6 +36,7 @@ #define PATH_TO_SDF_JOINT_PRISMATIC "@path_to_sdf_joint_prismatic@" #define PATH_TO_SDF_JOINT_REVOLUTE "@path_to_sdf_joint_revolute@" #define PATH_TO_SDF_JOINT_REVOLUTE2 "@path_to_sdf_joint_revolute2@" +#define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From ec10874d724d33fe39a77c19c50d328dbe7676b4 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 7 Oct 2020 09:58:25 -0700 Subject: [PATCH 090/152] Add joint_universal test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 9 +++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index bbc920bc..503d3b94 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -95,6 +95,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute" "joint_revolute") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute2" "joint_revolute2") sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index 962a3df1..9bc8ae21 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -148,3 +148,12 @@ TEST(Joint, joint_screw) EXPECT_FALSE(errors.empty()); ASSERT_FALSE(model); } + +TEST(Joint, joint_universal) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_UNIVERSAL), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index b3c5235b..e7bef3aa 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -37,6 +37,7 @@ #define PATH_TO_SDF_JOINT_REVOLUTE "@path_to_sdf_joint_revolute@" #define PATH_TO_SDF_JOINT_REVOLUTE2 "@path_to_sdf_joint_revolute2@" #define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" +#define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 0746ec65219068bf27e34237e43069871cb0f819 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 7 Oct 2020 15:33:00 -0700 Subject: [PATCH 091/152] Add link_inertia test Signed-off-by: Shane Loretz --- CMakeLists.txt | 7 +++++++ test/link_tests.cpp | 45 +++++++++++++++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 53 insertions(+) create mode 100644 test/link_tests.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 503d3b94..08e33a28 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -96,6 +96,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute2" "joint_revolute2") sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") + sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") @@ -131,6 +132,12 @@ if(BUILD_TESTING) "${CMAKE_CURRENT_SOURCE_DIR}/test/include" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_link_tests "test/link_tests.cpp") + target_link_libraries(sdf_link_tests sdformat_urdf) + target_include_directories(sdf_link_tests PRIVATE + "${CMAKE_CURRENT_SOURCE_DIR}/test/include" + "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_model_tests "test/model_tests.cpp") target_link_libraries(sdf_model_tests sdformat_urdf) target_include_directories(sdf_model_tests PRIVATE diff --git a/test/link_tests.cpp b/test/link_tests.cpp new file mode 100644 index 00000000..04906307 --- /dev/null +++ b/test/link_tests.cpp @@ -0,0 +1,45 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 +#include +#include +#include +#include + +#include "sdf_paths.hpp" +#include "test_tools.hpp" + +TEST(Link, link_inertia) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_LINK_INERTIA), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("link_inertia", model->getName()); + + urdf::LinkConstSharedPtr link = model->getLink("link"); + + EXPECT_EQ("link", link->name); + ASSERT_NE(nullptr, link->inertial); + EXPECT_DOUBLE_EQ(116.0, link->inertial->mass); + EXPECT_DOUBLE_EQ(5.652232699207, link->inertial->ixx); + EXPECT_DOUBLE_EQ(-0.009719934438, link->inertial->ixy); + EXPECT_DOUBLE_EQ(1.293988226423, link->inertial->ixz); + EXPECT_DOUBLE_EQ(5.669473158652, link->inertial->iyy); + EXPECT_DOUBLE_EQ(-0.007379583694, link->inertial->iyz); + EXPECT_DOUBLE_EQ(3.683196351726, link->inertial->izz); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index e7bef3aa..d1d46b24 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -38,6 +38,7 @@ #define PATH_TO_SDF_JOINT_REVOLUTE2 "@path_to_sdf_joint_revolute2@" #define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" #define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" +#define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 25d9a542ee4a2d32a014de104d6c31d308a380a1 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 7 Oct 2020 15:56:48 -0700 Subject: [PATCH 092/152] Add joint_revolute_axis test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 18 ++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 20 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 08e33a28..266f9ee0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -94,6 +94,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_prismatic" "joint_prismatic") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute" "joint_revolute") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute2" "joint_revolute2") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_axis" "joint_revolute_axis") sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index 9bc8ae21..38377899 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -140,6 +140,24 @@ TEST(Joint, joint_revolute2) ASSERT_FALSE(model); } +TEST(Joint, joint_revolute_axis) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_REVOLUTE_AXIS), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("joint_revolute_axis", model->getName()); + + urdf::JointConstSharedPtr joint = model->getJoint("joint_revolute"); + + EXPECT_EQ("joint_revolute", joint->name); + EXPECT_EQ(urdf::Joint::REVOLUTE, joint->type); + EXPECT_DOUBLE_EQ(0.1, joint->axis.x); + EXPECT_DOUBLE_EQ(1.23, joint->axis.y); + EXPECT_DOUBLE_EQ(4.567, joint->axis.z); +} + TEST(Joint, joint_screw) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index d1d46b24..f94e103d 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -36,6 +36,7 @@ #define PATH_TO_SDF_JOINT_PRISMATIC "@path_to_sdf_joint_prismatic@" #define PATH_TO_SDF_JOINT_REVOLUTE "@path_to_sdf_joint_revolute@" #define PATH_TO_SDF_JOINT_REVOLUTE2 "@path_to_sdf_joint_revolute2@" +#define PATH_TO_SDF_JOINT_REVOLUTE_AXIS "@path_to_sdf_joint_revolute_axis@" #define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" #define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" #define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" From 523a18d692f3188c784a2e731205c6d4c05b8b98 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 14:22:15 -0700 Subject: [PATCH 093/152] Warn on non-default values of unsupported tags Signed-off-by: Shane Loretz --- CMakeLists.txt | 3 +++ src/sdformat_urdf.cpp | 25 +++++++++++++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 266f9ee0..e41fa7c2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -34,6 +34,9 @@ target_include_directories(sdformat_urdf "$" ${urdfdom_headers_INCLUDE_DIRS} ) +ament_target_dependencies(sdformat_urdf PUBLIC + "rcutils" +) # Add sdformat_urdf_plugin module library add_library(sdformat_urdf_plugin MODULE diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index cab1c6f4..667a48c5 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include #include @@ -501,6 +502,18 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) urdf_joint->dynamics->damping = sdf_axis->Damping(); urdf_joint->dynamics->friction = sdf_axis->Friction(); + // Warn about non-default values on unsupported tags + if (0.0 != sdf_axis->SpringReference()) { + RCUTILS_LOG_WARN_NAMED( + "sdformat_urdf", "SDFormat Joint [%s] given non-default value for ," + " but URDF does not support this", sdf_joint.Name().c_str()); + } + if (0.0 != sdf_axis->SpringStiffness()) { + RCUTILS_LOG_WARN_NAMED( + "sdformat_urdf", "SDFormat Joint [%s] given non-default value for ," + " but URDF does not support this", sdf_joint.Name().c_str()); + } + // Add limits info for non-fixed non-continuous joints if (urdf::Joint::CONTINUOUS != urdf_joint->type) { urdf_joint->limits = std::make_shared(); @@ -508,6 +521,18 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) urdf_joint->limits->upper = sdf_axis->Upper(); urdf_joint->limits->effort = sdf_axis->Effort(); urdf_joint->limits->velocity = sdf_axis->MaxVelocity(); + + // Warn about non-default values on unsupported tags + if (1.0 != sdf_axis->Dissipation()) { + RCUTILS_LOG_WARN_NAMED( + "sdformat_urdf", "SDFormat Joint [%s] given non-default value for ," + " but URDF does not support this", sdf_joint.Name().c_str()); + } + if (1e8 != sdf_axis->Stiffness()) { + RCUTILS_LOG_WARN_NAMED( + "sdformat_urdf", "SDFormat Joint [%s] given non-default value for ," + " but URDF does not support this", sdf_joint.Name().c_str()); + } } } From 48156b5248d40b97ca67778a2629dcae4304241e Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 15:29:58 -0700 Subject: [PATCH 094/152] Add link_multiple_collisions test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/link_tests.cpp | 19 +++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 21 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index e41fa7c2..aa39e51e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -101,6 +101,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") + sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_collisions" "link_multiple_collisions") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/link_tests.cpp b/test/link_tests.cpp index 04906307..0506341e 100644 --- a/test/link_tests.cpp +++ b/test/link_tests.cpp @@ -43,3 +43,22 @@ TEST(Link, link_inertia) EXPECT_DOUBLE_EQ(-0.007379583694, link->inertial->iyz); EXPECT_DOUBLE_EQ(3.683196351726, link->inertial->izz); } + +TEST(Link, link_multiple_collisions) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_LINK_MULTIPLE_COLLISIONS), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("link_multiple_collisions", model->getName()); + + urdf::LinkConstSharedPtr link = model->getLink("link"); + + EXPECT_EQ("link", link->name); + ASSERT_NE(nullptr, link->collision); + ASSERT_EQ(2u, link->collision_array.size()); + ASSERT_EQ(link->collision, link->collision_array[0]); + EXPECT_EQ("link_collision_1", link->collision_array[0]->name); + EXPECT_EQ("link_collision_2", link->collision_array[1]->name); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index f94e103d..ba9c7c91 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -40,6 +40,7 @@ #define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" #define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" #define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" +#define PATH_TO_SDF_LINK_MULTIPLE_COLLISIONS "@path_to_sdf_link_multiple_collisions@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 5797057e25ecf23e0e71a4b9935f3bdfbd347c37 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 15:33:38 -0700 Subject: [PATCH 095/152] Add link_multiple_visuals test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/link_tests.cpp | 19 +++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 21 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index aa39e51e..06cc4ced 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -102,6 +102,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_collisions" "link_multiple_collisions") + sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_visuals" "link_multiple_visuals") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/link_tests.cpp b/test/link_tests.cpp index 0506341e..71924ad4 100644 --- a/test/link_tests.cpp +++ b/test/link_tests.cpp @@ -62,3 +62,22 @@ TEST(Link, link_multiple_collisions) EXPECT_EQ("link_collision_1", link->collision_array[0]->name); EXPECT_EQ("link_collision_2", link->collision_array[1]->name); } + +TEST(Link, link_multiple_visuals) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_LINK_MULTIPLE_VISUALS), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("link_multiple_visuals", model->getName()); + + urdf::LinkConstSharedPtr link = model->getLink("link"); + + EXPECT_EQ("link", link->name); + ASSERT_NE(nullptr, link->visual); + ASSERT_EQ(2u, link->visual_array.size()); + ASSERT_EQ(link->visual, link->visual_array[0]); + EXPECT_EQ("link_visual_1", link->visual_array[0]->name); + EXPECT_EQ("link_visual_2", link->visual_array[1]->name); +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index ba9c7c91..53dd5951 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -41,6 +41,7 @@ #define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" #define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" #define PATH_TO_SDF_LINK_MULTIPLE_COLLISIONS "@path_to_sdf_link_multiple_collisions@" +#define PATH_TO_SDF_LINK_MULTIPLE_VISUALS "@path_to_sdf_link_multiple_visuals@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 00b1aa74678b7e94b87fbe6df33778c62354bfb9 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 15:53:31 -0700 Subject: [PATCH 096/152] Add joint_revolute_axis_in_frame test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 30 ++++++++++++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 32 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 06cc4ced..0fd53c44 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -98,6 +98,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute" "joint_revolute") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute2" "joint_revolute2") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_axis" "joint_revolute_axis") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_axis_in_frame" "joint_revolute_axis_in_frame") sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index 38377899..e906a2fd 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -158,6 +158,36 @@ TEST(Joint, joint_revolute_axis) EXPECT_DOUBLE_EQ(4.567, joint->axis.z); } +TEST(Joint, joint_revolute_axis_in_frame) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_REVOLUTE_AXIS_IN_FRAME), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("joint_revolute_axis_in_frame", model->getName()); + + urdf::JointConstSharedPtr joint = model->getJoint("joint_revolute"); + + const ignition::math::Pose3d model_to_frame_in_model{0.05, 0.1, 0.2, 0.1, 0.2, 0.3}; + const ignition::math::Pose3d model_to_child_in_model{0.1, 0, 0.1, 0, 0, 0}; + const ignition::math::Pose3d frame_to_child_in_frame = + model_to_child_in_model - model_to_frame_in_model; + const ignition::math::Pose3d child_to_joint_in_child{0, 0, 0, 0, 0, 0}; + const ignition::math::Pose3d frame_to_joint_in_frame = + child_to_joint_in_child + frame_to_child_in_frame; + + const ignition::math::Vector3d axis_in_frame{0.1, 1.23, 4.567}; + const ignition::math::Vector3d axis_in_joint = + frame_to_joint_in_frame.Inverse().Rot().RotateVector(axis_in_frame); + + EXPECT_EQ("joint_revolute", joint->name); + EXPECT_EQ(urdf::Joint::REVOLUTE, joint->type); + EXPECT_DOUBLE_EQ(axis_in_joint.X(), joint->axis.x); + EXPECT_DOUBLE_EQ(axis_in_joint.Y(), joint->axis.y); + EXPECT_DOUBLE_EQ(axis_in_joint.Z(), joint->axis.z); +} + TEST(Joint, joint_screw) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 53dd5951..4f3a7c20 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -37,6 +37,7 @@ #define PATH_TO_SDF_JOINT_REVOLUTE "@path_to_sdf_joint_revolute@" #define PATH_TO_SDF_JOINT_REVOLUTE2 "@path_to_sdf_joint_revolute2@" #define PATH_TO_SDF_JOINT_REVOLUTE_AXIS "@path_to_sdf_joint_revolute_axis@" +#define PATH_TO_SDF_JOINT_REVOLUTE_AXIS_IN_FRAME "@path_to_sdf_joint_revolute_axis_in_frame@" #define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" #define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" #define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" From 4d9d79e8be66ca0ca7bf01b9b896e1e4c4832d96 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 16:11:21 -0700 Subject: [PATCH 097/152] Add joint_revolute_default_limits test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 20 ++++++++++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 22 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 0fd53c44..160eb1a5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -99,6 +99,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute2" "joint_revolute2") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_axis" "joint_revolute_axis") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_axis_in_frame" "joint_revolute_axis_in_frame") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_default_limits" "joint_revolute_default_limits") sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index e906a2fd..7e12c8e8 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -188,6 +188,26 @@ TEST(Joint, joint_revolute_axis_in_frame) EXPECT_DOUBLE_EQ(axis_in_joint.Z(), joint->axis.z); } +TEST(Joint, joint_revolute_default_limits) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_REVOLUTE_DEFAULT_LIMITS), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("joint_revolute_default_limits", model->getName()); + + urdf::JointConstSharedPtr joint = model->getJoint("joint_revolute"); + + EXPECT_EQ("joint_revolute", joint->name); + EXPECT_EQ(urdf::Joint::REVOLUTE, joint->type); + ASSERT_NE(nullptr, joint->limits); + EXPECT_DOUBLE_EQ(-1e16, joint->limits->lower); // SDFormat default + EXPECT_DOUBLE_EQ(1e16, joint->limits->upper); // SDFormat default + EXPECT_DOUBLE_EQ(-1, joint->limits->effort); // SDFormat default + EXPECT_DOUBLE_EQ(-1, joint->limits->velocity); // SDFormat default +} + TEST(Joint, joint_screw) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 4f3a7c20..53be01b7 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -38,6 +38,7 @@ #define PATH_TO_SDF_JOINT_REVOLUTE2 "@path_to_sdf_joint_revolute2@" #define PATH_TO_SDF_JOINT_REVOLUTE_AXIS "@path_to_sdf_joint_revolute_axis@" #define PATH_TO_SDF_JOINT_REVOLUTE_AXIS_IN_FRAME "@path_to_sdf_joint_revolute_axis_in_frame@" +#define PATH_TO_SDF_JOINT_REVOLUTE_DEFAULT_LIMITS "@path_to_sdf_joint_revolute_default_limits@" #define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" #define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" #define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" From 2d8dc1a8fc7b294b224c6f6d86f5bf41184695bc Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 16:54:24 -0700 Subject: [PATCH 098/152] Detect kinematic loops involving redundant joints Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 667a48c5..0a129152 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -247,6 +247,15 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) "Failed to get child link [" + child_link_name + "]"); return nullptr; } + + // Check for kinematic loops and redundant joints between two links + if (link_stack.end() != std::find(link_stack.begin(), link_stack.end(), sdf_child_link)) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Found kinematic loop at joint [" + sdf_joint->Name() + "]"); + return nullptr; + } + urdf::LinkSharedPtr & urdf_child_link = urdf_model->links_.at(child_link_name); // child link is attached to parent joint @@ -271,7 +280,7 @@ sdformat_urdf::convert_model(const sdf::Model & sdf_model, sdf::Errors & errors) // This link must be a child of two joints - kinematic loop :( errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Link can only be a child of one joint [" + sdf_parent_link->Name() + "]"); + "Link [" + sdf_parent_link->Name() + "] must only be a child of one joint"); } return nullptr; } else { From 9574007048aa487b33822904acc567fb20deff95 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 16:55:23 -0700 Subject: [PATCH 099/152] Add joint_revolute_two_joints_two_links test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/joint_tests.cpp | 9 +++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 11 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 160eb1a5..f5bdf4e8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -100,6 +100,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_axis" "joint_revolute_axis") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_axis_in_frame" "joint_revolute_axis_in_frame") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_default_limits" "joint_revolute_default_limits") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute_two_joints_two_links" "joint_revolute_two_joints_two_links") sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") diff --git a/test/joint_tests.cpp b/test/joint_tests.cpp index 7e12c8e8..100142ea 100644 --- a/test/joint_tests.cpp +++ b/test/joint_tests.cpp @@ -208,6 +208,15 @@ TEST(Joint, joint_revolute_default_limits) EXPECT_DOUBLE_EQ(-1, joint->limits->velocity); // SDFormat default } +TEST(Joint, joint_revolute_two_joints_two_links) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_REVOLUTE_TWO_JOINTS_TWO_LINKS), errors); + EXPECT_FALSE(errors.empty()); + ASSERT_FALSE(model); +} + TEST(Joint, joint_screw) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 53be01b7..b65114b1 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -39,6 +39,7 @@ #define PATH_TO_SDF_JOINT_REVOLUTE_AXIS "@path_to_sdf_joint_revolute_axis@" #define PATH_TO_SDF_JOINT_REVOLUTE_AXIS_IN_FRAME "@path_to_sdf_joint_revolute_axis_in_frame@" #define PATH_TO_SDF_JOINT_REVOLUTE_DEFAULT_LIMITS "@path_to_sdf_joint_revolute_default_limits@" +#define PATH_TO_SDF_JOINT_REVOLUTE_TWO_JOINTS_TWO_LINKS "@path_to_sdf_joint_revolute_two_joints_two_links@" #define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" #define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" #define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" From 3e4c49532e317eb3e7b9037ae6a1093c3d143e60 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 17:45:16 -0700 Subject: [PATCH 100/152] Warn if or are used on Signed-off-by: Shane Loretz --- src/sdformat_urdf.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/src/sdformat_urdf.cpp b/src/sdformat_urdf.cpp index 0a129152..8552a0f8 100644 --- a/src/sdformat_urdf.cpp +++ b/src/sdformat_urdf.cpp @@ -451,6 +451,18 @@ sdformat_urdf::convert_link( urdf_link->collision_array.push_back(urdf_collision); } + // Warn about unsupported features + if (0u != sdf_link.SensorCount()) { + RCUTILS_LOG_WARN_NAMED( + "sdformat_urdf", "SDFormat link [%s] has a ," + " but URDF does not support this", sdf_link.Name().c_str()); + } + if (0u != sdf_link.LightCount()) { + RCUTILS_LOG_WARN_NAMED( + "sdformat_urdf", "SDFormat link [%s] has a ," + " but URDF does not support this", sdf_link.Name().c_str()); + } + return urdf_link; } From 57520443e390ec5319ca199fc03b28fbac821e5d Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 17:45:34 -0700 Subject: [PATCH 101/152] Add link_sensor_imu test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/link_tests.cpp | 12 ++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 14 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index f5bdf4e8..4576910b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -106,6 +106,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_collisions" "link_multiple_collisions") sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_visuals" "link_multiple_visuals") + sdformat_test_files_get_model_sdf("path_to_sdf_link_sensor_imu" "link_sensor_imu") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/test/link_tests.cpp b/test/link_tests.cpp index 71924ad4..46f2fb07 100644 --- a/test/link_tests.cpp +++ b/test/link_tests.cpp @@ -81,3 +81,15 @@ TEST(Link, link_multiple_visuals) EXPECT_EQ("link_visual_1", link->visual_array[0]->name); EXPECT_EQ("link_visual_2", link->visual_array[1]->name); } + +TEST(Link, link_sensor_imu) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_LINK_SENSOR_IMU), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("link_sensor_imu", model->getName()); + + // Sensors are ignored, but warnings are emitted for their presense +} diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index b65114b1..1bd53e69 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -45,6 +45,7 @@ #define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" #define PATH_TO_SDF_LINK_MULTIPLE_COLLISIONS "@path_to_sdf_link_multiple_collisions@" #define PATH_TO_SDF_LINK_MULTIPLE_VISUALS "@path_to_sdf_link_multiple_visuals@" +#define PATH_TO_SDF_LINK_SENSOR_IMU "@path_to_sdf_link_sensor_imu@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 47754a16392bf9438626c0eadb80b69a29f226f0 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 17:50:05 -0700 Subject: [PATCH 102/152] Add link_light_point test Signed-off-by: Shane Loretz --- CMakeLists.txt | 1 + test/link_tests.cpp | 12 ++++++++++++ test/sdf_paths.hpp.in | 1 + 3 files changed, 14 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4576910b..9817649b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -104,6 +104,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_screw" "joint_screw") sdformat_test_files_get_model_sdf("path_to_sdf_joint_universal" "joint_universal") sdformat_test_files_get_model_sdf("path_to_sdf_link_inertia" "link_inertia") + sdformat_test_files_get_model_sdf("path_to_sdf_link_light_point" "link_light_point") sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_collisions" "link_multiple_collisions") sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_visuals" "link_multiple_visuals") sdformat_test_files_get_model_sdf("path_to_sdf_link_sensor_imu" "link_sensor_imu") diff --git a/test/link_tests.cpp b/test/link_tests.cpp index 46f2fb07..487ec129 100644 --- a/test/link_tests.cpp +++ b/test/link_tests.cpp @@ -44,6 +44,18 @@ TEST(Link, link_inertia) EXPECT_DOUBLE_EQ(3.683196351726, link->inertial->izz); } +TEST(Link, link_light_point) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_LINK_LIGHT_POINT), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("link_light_point", model->getName()); + + // Sensors are ignored, but warnings are emitted for their presense +} + TEST(Link, link_multiple_collisions) { sdf::Errors errors; diff --git a/test/sdf_paths.hpp.in b/test/sdf_paths.hpp.in index 1bd53e69..ef66a1ae 100644 --- a/test/sdf_paths.hpp.in +++ b/test/sdf_paths.hpp.in @@ -43,6 +43,7 @@ #define PATH_TO_SDF_JOINT_SCREW "@path_to_sdf_joint_screw@" #define PATH_TO_SDF_JOINT_UNIVERSAL "@path_to_sdf_joint_universal@" #define PATH_TO_SDF_LINK_INERTIA "@path_to_sdf_link_inertia@" +#define PATH_TO_SDF_LINK_LIGHT_POINT "@path_to_sdf_link_light_point@" #define PATH_TO_SDF_LINK_MULTIPLE_COLLISIONS "@path_to_sdf_link_multiple_collisions@" #define PATH_TO_SDF_LINK_MULTIPLE_VISUALS "@path_to_sdf_link_multiple_visuals@" #define PATH_TO_SDF_LINK_SENSOR_IMU "@path_to_sdf_link_sensor_imu@" From d8c59b822639b8c0b71315fe408c048e2f7adc23 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 18:00:56 -0700 Subject: [PATCH 103/152] Sensors -> lights Signed-off-by: Shane Loretz --- test/link_tests.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/link_tests.cpp b/test/link_tests.cpp index 487ec129..0d3cc591 100644 --- a/test/link_tests.cpp +++ b/test/link_tests.cpp @@ -53,7 +53,7 @@ TEST(Link, link_light_point) ASSERT_TRUE(model); ASSERT_EQ("link_light_point", model->getName()); - // Sensors are ignored, but warnings are emitted for their presense + // lights are ignored, but warnings are emitted for their presense } TEST(Link, link_multiple_collisions) From cafee114366a157fc751d83331c34b77c36c31f1 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 18:03:57 -0700 Subject: [PATCH 104/152] Move package into folder in repo Signed-off-by: Shane Loretz --- CMakeLists.txt => sdformat_urdf/CMakeLists.txt | 0 CONTRIBUTING.md => sdformat_urdf/CONTRIBUTING.md | 0 LICENSE => sdformat_urdf/LICENSE | 0 .../include}/sdformat_urdf/sdformat_urdf.hpp | 0 .../include}/sdformat_urdf/visibility_control.hpp | 0 package.xml => sdformat_urdf/package.xml | 0 .../sdformat_urdf_plugin.xml | 0 {src => sdformat_urdf/src}/sdformat_urdf.cpp | 0 {src => sdformat_urdf/src}/sdformat_urdf_plugin.cpp | 0 {test => sdformat_urdf/test}/geometry_tests.cpp | 0 {test => sdformat_urdf/test}/graph_tests.cpp | 0 {test => sdformat_urdf/test}/include/test_tools.hpp | 0 {test => sdformat_urdf/test}/joint_tests.cpp | 0 {test => sdformat_urdf/test}/link_tests.cpp | 0 {test => sdformat_urdf/test}/model_tests.cpp | 0 {test => sdformat_urdf/test}/pose_tests.cpp | 0 {test => sdformat_urdf/test}/sdf_paths.hpp.in | 0 17 files changed, 0 insertions(+), 0 deletions(-) rename CMakeLists.txt => sdformat_urdf/CMakeLists.txt (100%) rename CONTRIBUTING.md => sdformat_urdf/CONTRIBUTING.md (100%) rename LICENSE => sdformat_urdf/LICENSE (100%) rename {include => sdformat_urdf/include}/sdformat_urdf/sdformat_urdf.hpp (100%) rename {include => sdformat_urdf/include}/sdformat_urdf/visibility_control.hpp (100%) rename package.xml => sdformat_urdf/package.xml (100%) rename sdformat_urdf_plugin.xml => sdformat_urdf/sdformat_urdf_plugin.xml (100%) rename {src => sdformat_urdf/src}/sdformat_urdf.cpp (100%) rename {src => sdformat_urdf/src}/sdformat_urdf_plugin.cpp (100%) rename {test => sdformat_urdf/test}/geometry_tests.cpp (100%) rename {test => sdformat_urdf/test}/graph_tests.cpp (100%) rename {test => sdformat_urdf/test}/include/test_tools.hpp (100%) rename {test => sdformat_urdf/test}/joint_tests.cpp (100%) rename {test => sdformat_urdf/test}/link_tests.cpp (100%) rename {test => sdformat_urdf/test}/model_tests.cpp (100%) rename {test => sdformat_urdf/test}/pose_tests.cpp (100%) rename {test => sdformat_urdf/test}/sdf_paths.hpp.in (100%) diff --git a/CMakeLists.txt b/sdformat_urdf/CMakeLists.txt similarity index 100% rename from CMakeLists.txt rename to sdformat_urdf/CMakeLists.txt diff --git a/CONTRIBUTING.md b/sdformat_urdf/CONTRIBUTING.md similarity index 100% rename from CONTRIBUTING.md rename to sdformat_urdf/CONTRIBUTING.md diff --git a/LICENSE b/sdformat_urdf/LICENSE similarity index 100% rename from LICENSE rename to sdformat_urdf/LICENSE diff --git a/include/sdformat_urdf/sdformat_urdf.hpp b/sdformat_urdf/include/sdformat_urdf/sdformat_urdf.hpp similarity index 100% rename from include/sdformat_urdf/sdformat_urdf.hpp rename to sdformat_urdf/include/sdformat_urdf/sdformat_urdf.hpp diff --git a/include/sdformat_urdf/visibility_control.hpp b/sdformat_urdf/include/sdformat_urdf/visibility_control.hpp similarity index 100% rename from include/sdformat_urdf/visibility_control.hpp rename to sdformat_urdf/include/sdformat_urdf/visibility_control.hpp diff --git a/package.xml b/sdformat_urdf/package.xml similarity index 100% rename from package.xml rename to sdformat_urdf/package.xml diff --git a/sdformat_urdf_plugin.xml b/sdformat_urdf/sdformat_urdf_plugin.xml similarity index 100% rename from sdformat_urdf_plugin.xml rename to sdformat_urdf/sdformat_urdf_plugin.xml diff --git a/src/sdformat_urdf.cpp b/sdformat_urdf/src/sdformat_urdf.cpp similarity index 100% rename from src/sdformat_urdf.cpp rename to sdformat_urdf/src/sdformat_urdf.cpp diff --git a/src/sdformat_urdf_plugin.cpp b/sdformat_urdf/src/sdformat_urdf_plugin.cpp similarity index 100% rename from src/sdformat_urdf_plugin.cpp rename to sdformat_urdf/src/sdformat_urdf_plugin.cpp diff --git a/test/geometry_tests.cpp b/sdformat_urdf/test/geometry_tests.cpp similarity index 100% rename from test/geometry_tests.cpp rename to sdformat_urdf/test/geometry_tests.cpp diff --git a/test/graph_tests.cpp b/sdformat_urdf/test/graph_tests.cpp similarity index 100% rename from test/graph_tests.cpp rename to sdformat_urdf/test/graph_tests.cpp diff --git a/test/include/test_tools.hpp b/sdformat_urdf/test/include/test_tools.hpp similarity index 100% rename from test/include/test_tools.hpp rename to sdformat_urdf/test/include/test_tools.hpp diff --git a/test/joint_tests.cpp b/sdformat_urdf/test/joint_tests.cpp similarity index 100% rename from test/joint_tests.cpp rename to sdformat_urdf/test/joint_tests.cpp diff --git a/test/link_tests.cpp b/sdformat_urdf/test/link_tests.cpp similarity index 100% rename from test/link_tests.cpp rename to sdformat_urdf/test/link_tests.cpp diff --git a/test/model_tests.cpp b/sdformat_urdf/test/model_tests.cpp similarity index 100% rename from test/model_tests.cpp rename to sdformat_urdf/test/model_tests.cpp diff --git a/test/pose_tests.cpp b/sdformat_urdf/test/pose_tests.cpp similarity index 100% rename from test/pose_tests.cpp rename to sdformat_urdf/test/pose_tests.cpp diff --git a/test/sdf_paths.hpp.in b/sdformat_urdf/test/sdf_paths.hpp.in similarity index 100% rename from test/sdf_paths.hpp.in rename to sdformat_urdf/test/sdf_paths.hpp.in From e6b4f874c78d228452e858d95a50a6823c0b7b7b Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 18:06:22 -0700 Subject: [PATCH 105/152] Add sdformat_test_files package to repo Signed-off-by: Shane Loretz --- sdformat_test_files/CMakeLists.txt | 100 + .../models/geometry_box/geometry_box.sdf | 32 + .../models/geometry_box/model.config | 15 + .../geometry_cylinder/geometry_cylinder.sdf | 34 + .../models/geometry_cylinder/model.config | 15 + .../geometry_heightmap/geometry_heightmap.sdf | 34 + .../models/geometry_heightmap/heightmap.png | Bin 0 -> 11491 bytes .../models/geometry_heightmap/model.config | 14 + .../geometry_mesh_collada.sdf | 34 + .../models/geometry_mesh_collada/model.config | 15 + .../models/geometry_mesh_collada/torus.dae | 126 + .../geometry_mesh_obj/geometry_mesh_obj.sdf | 34 + .../models/geometry_mesh_obj/model.config | 15 + .../models/geometry_mesh_obj/torus.mtl | 12 + .../models/geometry_mesh_obj/torus.obj | 2083 +++++++++++++++++ .../geometry_mesh_scaled.sdf | 34 + .../models/geometry_mesh_scaled/model.config | 14 + .../models/geometry_mesh_scaled/torus.stl | Bin 0 -> 57684 bytes .../geometry_mesh_stl/geometry_mesh_stl.sdf | 34 + .../models/geometry_mesh_stl/model.config | 15 + .../models/geometry_mesh_stl/torus.stl | Bin 0 -> 57684 bytes .../models/geometry_plane/geometry_plane.sdf | 35 + .../models/geometry_plane/model.config | 15 + .../geometry_sphere/geometry_sphere.sdf | 32 + .../models/geometry_sphere/model.config | 15 + .../models/graph_chain/graph_chain.sdf | 103 + .../models/graph_chain/model.config | 14 + .../graph_chain_non_canonical_root.sdf | 103 + .../model.config | 14 + .../models/graph_four_bar/graph_four_bar.sdf | 146 ++ .../models/graph_four_bar/model.config | 14 + .../models/graph_loop/graph_loop.sdf | 110 + .../models/graph_loop/model.config | 14 + .../models/graph_tree/graph_tree.sdf | 208 ++ .../models/graph_tree/model.config | 14 + .../graph_tree_non_canonical_root.sdf | 208 ++ .../model.config | 14 + .../models/joint_ball/joint_ball.sdf | 65 + .../models/joint_ball/model.config | 15 + .../joint_continuous/joint_continuous.sdf | 68 + .../models/joint_continuous/model.config | 15 + .../models/joint_fixed/joint_fixed.sdf | 65 + .../models/joint_fixed/model.config | 15 + .../models/joint_gearbox/joint_gearbox.sdf | 32 + .../models/joint_gearbox/model.config | 15 + .../joint_prismatic/joint_prismatic.sdf | 72 + .../models/joint_prismatic/model.config | 15 + .../models/joint_revolute/joint_revolute.sdf | 72 + .../models/joint_revolute/model.config | 15 + .../joint_revolute2/joint_revolute2.sdf | 80 + .../models/joint_revolute2/model.config | 15 + .../joint_revolute_axis.sdf | 72 + .../models/joint_revolute_axis/model.config | 14 + .../joint_revolute_axis_in_frame.sdf | 75 + .../joint_revolute_axis_in_frame/model.config | 14 + .../joint_revolute_default_limits.sdf | 68 + .../model.config | 14 + .../joint_revolute_two_joints_two_links.sdf | 84 + .../model.config | 14 + .../models/joint_screw/joint_screw.sdf | 73 + .../models/joint_screw/model.config | 15 + .../joint_universal/joint_universal.sdf | 66 + .../models/joint_universal/model.config | 15 + .../models/link_inertia/link_inertia.sdf | 32 + .../models/link_inertia/model.config | 14 + .../link_light_point/link_light_point.sdf | 33 + .../models/link_light_point/model.config | 14 + .../link_multiple_collisions.sdf | 39 + .../link_multiple_collisions/model.config | 14 + .../link_multiple_visuals.sdf | 39 + .../models/link_multiple_visuals/model.config | 14 + .../link_sensor_imu/link_sensor_imu.sdf | 35 + .../models/link_sensor_imu/model.config | 14 + .../material_blinn_phong.sdf | 38 + .../models/material_blinn_phong/model.config | 15 + .../material_dynamic_lights.sdf | 52 + .../material_dynamic_lights/model.config | 15 + .../material_ogre_script.sdf | 32 + .../models/material_ogre_script/model.config | 14 + .../models/material_pbr/material_pbr.sdf | 32 + .../models/material_pbr/model.config | 14 + .../material_shader/material_shader.sdf | 32 + .../models/material_shader/model.config | 14 + .../models/model_two_models/model.config | 14 + .../model_two_models/model_two_models.sdf | 61 + .../models/model_zero_models/model.config | 14 + .../model_zero_models/model_zero_models.sdf | 3 + .../models/pose_chain/model.config | 14 + .../models/pose_chain/pose_chain.sdf | 153 ++ .../models/pose_collision/model.config | 14 + .../models/pose_collision/pose_collision.sdf | 33 + .../pose_collision_in_frame/model.config | 14 + .../pose_collision_in_frame.sdf | 36 + .../models/pose_inertial/model.config | 14 + .../models/pose_inertial/pose_inertial.sdf | 33 + .../pose_inertial_in_frame/model.config | 14 + .../pose_inertial_in_frame.sdf | 36 + .../models/pose_joint/model.config | 14 + .../models/pose_joint/pose_joint.sdf | 71 + .../models/pose_joint_in_frame/model.config | 14 + .../pose_joint_in_frame.sdf | 74 + .../models/pose_link/model.config | 14 + .../models/pose_link/pose_link.sdf | 33 + .../models/pose_link_all/model.config | 14 + .../models/pose_link_all/pose_link_all.sdf | 36 + .../models/pose_link_in_frame/model.config | 14 + .../pose_link_in_frame/pose_link_in_frame.sdf | 36 + .../models/pose_model/model.config | 14 + .../models/pose_model/pose_model.sdf | 33 + .../models/pose_visual/model.config | 14 + .../models/pose_visual/pose_visual.sdf | 33 + .../models/pose_visual_in_frame/model.config | 14 + .../pose_visual_in_frame.sdf | 36 + sdformat_test_files/package.xml | 23 + .../sdformat_test_filesConfig.cmake.in | 7 + .../sdformat_test_files_functions.cmake.in | 32 + 116 files changed, 6287 insertions(+) create mode 100644 sdformat_test_files/CMakeLists.txt create mode 100644 sdformat_test_files/models/geometry_box/geometry_box.sdf create mode 100644 sdformat_test_files/models/geometry_box/model.config create mode 100644 sdformat_test_files/models/geometry_cylinder/geometry_cylinder.sdf create mode 100644 sdformat_test_files/models/geometry_cylinder/model.config create mode 100644 sdformat_test_files/models/geometry_heightmap/geometry_heightmap.sdf create mode 100644 sdformat_test_files/models/geometry_heightmap/heightmap.png create mode 100644 sdformat_test_files/models/geometry_heightmap/model.config create mode 100644 sdformat_test_files/models/geometry_mesh_collada/geometry_mesh_collada.sdf create mode 100644 sdformat_test_files/models/geometry_mesh_collada/model.config create mode 100644 sdformat_test_files/models/geometry_mesh_collada/torus.dae create mode 100644 sdformat_test_files/models/geometry_mesh_obj/geometry_mesh_obj.sdf create mode 100644 sdformat_test_files/models/geometry_mesh_obj/model.config create mode 100644 sdformat_test_files/models/geometry_mesh_obj/torus.mtl create mode 100644 sdformat_test_files/models/geometry_mesh_obj/torus.obj create mode 100644 sdformat_test_files/models/geometry_mesh_scaled/geometry_mesh_scaled.sdf create mode 100644 sdformat_test_files/models/geometry_mesh_scaled/model.config create mode 100644 sdformat_test_files/models/geometry_mesh_scaled/torus.stl create mode 100644 sdformat_test_files/models/geometry_mesh_stl/geometry_mesh_stl.sdf create mode 100644 sdformat_test_files/models/geometry_mesh_stl/model.config create mode 100644 sdformat_test_files/models/geometry_mesh_stl/torus.stl create mode 100644 sdformat_test_files/models/geometry_plane/geometry_plane.sdf create mode 100644 sdformat_test_files/models/geometry_plane/model.config create mode 100644 sdformat_test_files/models/geometry_sphere/geometry_sphere.sdf create mode 100644 sdformat_test_files/models/geometry_sphere/model.config create mode 100644 sdformat_test_files/models/graph_chain/graph_chain.sdf create mode 100644 sdformat_test_files/models/graph_chain/model.config create mode 100644 sdformat_test_files/models/graph_chain_non_canonical_root/graph_chain_non_canonical_root.sdf create mode 100644 sdformat_test_files/models/graph_chain_non_canonical_root/model.config create mode 100644 sdformat_test_files/models/graph_four_bar/graph_four_bar.sdf create mode 100644 sdformat_test_files/models/graph_four_bar/model.config create mode 100644 sdformat_test_files/models/graph_loop/graph_loop.sdf create mode 100644 sdformat_test_files/models/graph_loop/model.config create mode 100644 sdformat_test_files/models/graph_tree/graph_tree.sdf create mode 100644 sdformat_test_files/models/graph_tree/model.config create mode 100644 sdformat_test_files/models/graph_tree_non_canonical_root/graph_tree_non_canonical_root.sdf create mode 100644 sdformat_test_files/models/graph_tree_non_canonical_root/model.config create mode 100644 sdformat_test_files/models/joint_ball/joint_ball.sdf create mode 100644 sdformat_test_files/models/joint_ball/model.config create mode 100644 sdformat_test_files/models/joint_continuous/joint_continuous.sdf create mode 100644 sdformat_test_files/models/joint_continuous/model.config create mode 100644 sdformat_test_files/models/joint_fixed/joint_fixed.sdf create mode 100644 sdformat_test_files/models/joint_fixed/model.config create mode 100644 sdformat_test_files/models/joint_gearbox/joint_gearbox.sdf create mode 100644 sdformat_test_files/models/joint_gearbox/model.config create mode 100644 sdformat_test_files/models/joint_prismatic/joint_prismatic.sdf create mode 100644 sdformat_test_files/models/joint_prismatic/model.config create mode 100644 sdformat_test_files/models/joint_revolute/joint_revolute.sdf create mode 100644 sdformat_test_files/models/joint_revolute/model.config create mode 100644 sdformat_test_files/models/joint_revolute2/joint_revolute2.sdf create mode 100644 sdformat_test_files/models/joint_revolute2/model.config create mode 100644 sdformat_test_files/models/joint_revolute_axis/joint_revolute_axis.sdf create mode 100644 sdformat_test_files/models/joint_revolute_axis/model.config create mode 100644 sdformat_test_files/models/joint_revolute_axis_in_frame/joint_revolute_axis_in_frame.sdf create mode 100644 sdformat_test_files/models/joint_revolute_axis_in_frame/model.config create mode 100644 sdformat_test_files/models/joint_revolute_default_limits/joint_revolute_default_limits.sdf create mode 100644 sdformat_test_files/models/joint_revolute_default_limits/model.config create mode 100644 sdformat_test_files/models/joint_revolute_two_joints_two_links/joint_revolute_two_joints_two_links.sdf create mode 100644 sdformat_test_files/models/joint_revolute_two_joints_two_links/model.config create mode 100644 sdformat_test_files/models/joint_screw/joint_screw.sdf create mode 100644 sdformat_test_files/models/joint_screw/model.config create mode 100644 sdformat_test_files/models/joint_universal/joint_universal.sdf create mode 100644 sdformat_test_files/models/joint_universal/model.config create mode 100644 sdformat_test_files/models/link_inertia/link_inertia.sdf create mode 100644 sdformat_test_files/models/link_inertia/model.config create mode 100644 sdformat_test_files/models/link_light_point/link_light_point.sdf create mode 100644 sdformat_test_files/models/link_light_point/model.config create mode 100644 sdformat_test_files/models/link_multiple_collisions/link_multiple_collisions.sdf create mode 100644 sdformat_test_files/models/link_multiple_collisions/model.config create mode 100644 sdformat_test_files/models/link_multiple_visuals/link_multiple_visuals.sdf create mode 100644 sdformat_test_files/models/link_multiple_visuals/model.config create mode 100644 sdformat_test_files/models/link_sensor_imu/link_sensor_imu.sdf create mode 100644 sdformat_test_files/models/link_sensor_imu/model.config create mode 100644 sdformat_test_files/models/material_blinn_phong/material_blinn_phong.sdf create mode 100644 sdformat_test_files/models/material_blinn_phong/model.config create mode 100644 sdformat_test_files/models/material_dynamic_lights/material_dynamic_lights.sdf create mode 100644 sdformat_test_files/models/material_dynamic_lights/model.config create mode 100644 sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf create mode 100644 sdformat_test_files/models/material_ogre_script/model.config create mode 100644 sdformat_test_files/models/material_pbr/material_pbr.sdf create mode 100644 sdformat_test_files/models/material_pbr/model.config create mode 100644 sdformat_test_files/models/material_shader/material_shader.sdf create mode 100644 sdformat_test_files/models/material_shader/model.config create mode 100644 sdformat_test_files/models/model_two_models/model.config create mode 100644 sdformat_test_files/models/model_two_models/model_two_models.sdf create mode 100644 sdformat_test_files/models/model_zero_models/model.config create mode 100644 sdformat_test_files/models/model_zero_models/model_zero_models.sdf create mode 100644 sdformat_test_files/models/pose_chain/model.config create mode 100644 sdformat_test_files/models/pose_chain/pose_chain.sdf create mode 100644 sdformat_test_files/models/pose_collision/model.config create mode 100644 sdformat_test_files/models/pose_collision/pose_collision.sdf create mode 100644 sdformat_test_files/models/pose_collision_in_frame/model.config create mode 100644 sdformat_test_files/models/pose_collision_in_frame/pose_collision_in_frame.sdf create mode 100644 sdformat_test_files/models/pose_inertial/model.config create mode 100644 sdformat_test_files/models/pose_inertial/pose_inertial.sdf create mode 100644 sdformat_test_files/models/pose_inertial_in_frame/model.config create mode 100644 sdformat_test_files/models/pose_inertial_in_frame/pose_inertial_in_frame.sdf create mode 100644 sdformat_test_files/models/pose_joint/model.config create mode 100644 sdformat_test_files/models/pose_joint/pose_joint.sdf create mode 100644 sdformat_test_files/models/pose_joint_in_frame/model.config create mode 100644 sdformat_test_files/models/pose_joint_in_frame/pose_joint_in_frame.sdf create mode 100644 sdformat_test_files/models/pose_link/model.config create mode 100644 sdformat_test_files/models/pose_link/pose_link.sdf create mode 100644 sdformat_test_files/models/pose_link_all/model.config create mode 100644 sdformat_test_files/models/pose_link_all/pose_link_all.sdf create mode 100644 sdformat_test_files/models/pose_link_in_frame/model.config create mode 100644 sdformat_test_files/models/pose_link_in_frame/pose_link_in_frame.sdf create mode 100644 sdformat_test_files/models/pose_model/model.config create mode 100644 sdformat_test_files/models/pose_model/pose_model.sdf create mode 100644 sdformat_test_files/models/pose_visual/model.config create mode 100644 sdformat_test_files/models/pose_visual/pose_visual.sdf create mode 100644 sdformat_test_files/models/pose_visual_in_frame/model.config create mode 100644 sdformat_test_files/models/pose_visual_in_frame/pose_visual_in_frame.sdf create mode 100644 sdformat_test_files/package.xml create mode 100644 sdformat_test_files/sdformat_test_filesConfig.cmake.in create mode 100644 sdformat_test_files/sdformat_test_files_functions.cmake.in diff --git a/sdformat_test_files/CMakeLists.txt b/sdformat_test_files/CMakeLists.txt new file mode 100644 index 00000000..fc023dd3 --- /dev/null +++ b/sdformat_test_files/CMakeLists.txt @@ -0,0 +1,100 @@ +cmake_minimum_required(VERSION 3.5) +project(sdformat_test_files) + +set(sdformat_test_files_VERSION 0.1.0) + +# Decide where to install stuff +include(GNUInstallDirs) + +set(INSTALL_SHARE_DIR "${CMAKE_INSTALL_DATAROOTDIR}/sdformat_test_files" CACHE PATH + "Installation directory for arch independent data files") + +set(INSTALL_CMAKE_DIR "${CMAKE_INSTALL_DATAROOTDIR}/sdformat_test_files/cmake" CACHE PATH + "Installation directory for CMake files") + +# Install models +set(model_names + "geometry_box" + "geometry_cylinder" + "geometry_heightmap" + "geometry_mesh_collada" + "geometry_mesh_obj" + "geometry_mesh_scaled" + "geometry_mesh_stl" + "geometry_plane" + "geometry_sphere" + "graph_chain" + "graph_chain_non_canonical_root" + "graph_four_bar" + "graph_loop" + "graph_tree" + "graph_tree_non_canonical_root" + "joint_ball" + "joint_continuous" + "joint_fixed" + "joint_gearbox" + "joint_prismatic" + "joint_revolute" + "joint_revolute2" + "joint_revolute_axis" + "joint_revolute_axis_in_frame" + "joint_revolute_default_limits" + "joint_revolute_two_joints_two_links" + "joint_screw" + "joint_universal" + "link_inertia" + "link_light_point" + "link_multiple_collisions" + "link_multiple_visuals" + "link_sensor_imu" + "material_blinn_phong" + "material_dynamic_lights" + "material_ogre_script" + "material_pbr" + "material_shader" + "model_two_models" + "model_zero_models" + "pose_chain" + "pose_collision" + "pose_collision_in_frame" + "pose_inertial" + "pose_inertial_in_frame" + "pose_joint" + "pose_joint_in_frame" + "pose_link" + "pose_link_all" + "pose_link_in_frame" + "pose_model" + "pose_visual" + "pose_visual_in_frame" +) + +foreach(model ${model_names}) + # Install models to share/project-name/model-name + install(DIRECTORY "models/${model}" DESTINATION "${INSTALL_SHARE_DIR}/models") +endforeach() + +# Create projectConfigVersion.cmake +include(CMakePackageConfigHelpers) +write_basic_package_version_file( + "${CMAKE_CURRENT_BINARY_DIR}/sdformat_test_files/sdformat_test_filesConfigVersion.cmake" + VERSION "${sdformat_test_files_VERSION}" + COMPATIBILITY SameMajorVersion + ARCH_INDEPENDENT) + +# Create projectConfig.cmake +configure_package_config_file("sdformat_test_filesConfig.cmake.in" + "${CMAKE_CURRENT_BINARY_DIR}/sdformat_test_files/sdformat_test_filesConfig.cmake" + INSTALL_DESTINATION "${INSTALL_CMAKE_DIR}" + PATH_VARS "INSTALL_CMAKE_DIR" "INSTALL_SHARE_DIR") + +# Create file with CMake functions +configure_file("sdformat_test_files_functions.cmake.in" + "${CMAKE_CURRENT_BINARY_DIR}/sdformat_test_files/sdformat_test_files_functions.cmake" @ONLY) + +# Install cmake files +install(FILES + "${CMAKE_CURRENT_BINARY_DIR}/sdformat_test_files/sdformat_test_filesConfig.cmake" + "${CMAKE_CURRENT_BINARY_DIR}/sdformat_test_files/sdformat_test_filesConfigVersion.cmake" + "${CMAKE_CURRENT_BINARY_DIR}/sdformat_test_files/sdformat_test_files_functions.cmake" + DESTINATION "${INSTALL_CMAKE_DIR}") diff --git a/sdformat_test_files/models/geometry_box/geometry_box.sdf b/sdformat_test_files/models/geometry_box/geometry_box.sdf new file mode 100644 index 00000000..80d3f478 --- /dev/null +++ b/sdformat_test_files/models/geometry_box/geometry_box.sdf @@ -0,0 +1,32 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/geometry_box/model.config b/sdformat_test_files/models/geometry_box/model.config new file mode 100644 index 00000000..1d8c2c7d --- /dev/null +++ b/sdformat_test_files/models/geometry_box/model.config @@ -0,0 +1,15 @@ + + + geometry_box + 1.0 + geometry_box.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + A box using only the box geometry type for both the visual and collision and a color. + + diff --git a/sdformat_test_files/models/geometry_cylinder/geometry_cylinder.sdf b/sdformat_test_files/models/geometry_cylinder/geometry_cylinder.sdf new file mode 100644 index 00000000..91213e74 --- /dev/null +++ b/sdformat_test_files/models/geometry_cylinder/geometry_cylinder.sdf @@ -0,0 +1,34 @@ + + + + + + + + 0.2 + 0.125 + + + + + + + 0.2 + 0.125 + + + + + 1.23 + + 0.0076875 + 0 + 0 + 0.0076875 + 0 + 0.0076875 + + + + + diff --git a/sdformat_test_files/models/geometry_cylinder/model.config b/sdformat_test_files/models/geometry_cylinder/model.config new file mode 100644 index 00000000..9bc60ccf --- /dev/null +++ b/sdformat_test_files/models/geometry_cylinder/model.config @@ -0,0 +1,15 @@ + + + geometry_cylinder + 1.0 + geometry_cylinder.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + A cylinder using only the cylinder geometry type for both the visual and collision and a color. + + diff --git a/sdformat_test_files/models/geometry_heightmap/geometry_heightmap.sdf b/sdformat_test_files/models/geometry_heightmap/geometry_heightmap.sdf new file mode 100644 index 00000000..ee183381 --- /dev/null +++ b/sdformat_test_files/models/geometry_heightmap/geometry_heightmap.sdf @@ -0,0 +1,34 @@ + + + + + + + + heightmap.png + 1 1 0.5 + + + + + + + heightmap.png + 1 1 0.5 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/geometry_heightmap/heightmap.png b/sdformat_test_files/models/geometry_heightmap/heightmap.png new file mode 100644 index 0000000000000000000000000000000000000000..5a83b40825d36c7ea9cf8d7553685c7301bc5bb0 GIT binary patch literal 11491 zcmW++2Q-{b7e)|0TJ+upL00cQIw3@hwye6^s?kdjtlqmsbb{4;FJbjwqepbB*MGnN z-7`Dq%z57_ckbMI?sM-qZO!-iI8-<&C@Axpul+0`jWaCSB6%ECg+b?O!S#e}&x$RL<7*JFcWIuW@ zL35Vfs8xuqNMsVwRa}=GpPpZO&4UKMup~ASZc5p<-Tj#$vCrsM_#jj82Jo(mjxK9_ zd_3>huU}cc8+>DXh?`r)9tAMw$Wz?2b#=k1acgfp@4o_sEyln>0A!;_cm?h zuEW}JV0Cr1skN1Qr1rmo1}K1rsh0to#nVHNdE(i^N22=Kf=2fRbUdihrPKsk7q9v-PoatksY^s!`q}hW*Wm8 zEai?Ev!QXv#^v$@5I{;wYVL#vXo8JO&k%Tgaxz%UeGsm6b8~ldV?fTjUbB2OFgQ3k zYZLhN(2R4u<7Rlm`aCu+fpY7$_I!56j}+>cJmhoW#XC|frAzks^c3J9j+_qv07db% zUAumVu)`+)#T{+j;MvntM~Cq9xa1~R9^5Niv$%#PZctASW`4WLO-lccd|1Q#2eP{q z!c&C?X?lA4Ptj=+8`o~AZjURt@l_I*8l^ncN3*z`gbeb!QvQ;L#~~?oua0uW|HQNP5;n>7>eVY?>uT)${Jg6K-LJY_j36UP zG#N;})O!}bvcxR9`a{L-7cRO@L#?Y$DLT1bCcJrZN(Dh@OIdJ`Ua=@q+KBaMhVrqD zE=6hsu8G~ZBei9d*-p4N0%Ny+bc0)GsxGysE2KEGRe1-yrj}EVQJjVR%)pql$NOs! z05kek0f+Lf*Kx+v?|pYFT(CCTB6|>Sg0#;9Qe^`ug#q)0Ia^AQEw|n$QydK;sjSpa z9u$fF#-|$qJmBrfx#DyT|G=%^lVz507W`k~PRIU%LiKn2T2qM>6Xq(1nY$e~%81^L z-$Ze@MP&KRYSR?Zq?6J0Xf2GR<;o;Q5Auy+>_-2q7fQ%YpRsMFwue-sHFEs6PeGB3=U3Kkh~WOBa}sfV5UN&P~L$1l7ZYTvcNL3u@R z&4yOvZDE7^evglQ{Dec`0nN9~Fs7s%xwY1DSwg4d7rI6_@-L6Pa_ecEkOyG)c&fXw z+LfONtNGVsfHWN)T~)ROj%*tuEFZ6u@&oedK#^i7b8!kVHO<1Rd=)vLvIH);9>ov=>_QTJs7F z>~vzPcW?x}QXA>r78sW^kBC2-xQi3qXu+&&ZeyS&!3iPnW&^UJuV_1A(tp`aL0r4% zdbg*ehP(27j4?|XM;eG(QUOMn8QJbk9=|!pvh1GWOW@m(YjV_THjiYbN}Ifaf;Nc6 zL+n@Lr5>4ZAQ`$dW)gS6S-Z)Mh+iX1`qDo?DKl#TC(W5B%!d@sX5z*XJLSJs%kksZ zeqAgIUb16D7toziUF2p<$mH$g=o&8YOU35QlzNgD945ZE%IfSu-Cs10H72vV+T7fk zIR^mt;#GczB^w4QyUWqz1Pc;E$YV{<&y`%dYZu#`rRBrAHPa!4JkGLt7LCi$>HP~< zX<5M0y7(Q^DBUn&5xGPh;PNWBZVOmxCJ4$yb}NK(9yWShLv1!b*G3UoKqSK@&l*U? zTx-%rYJ|Qc?ht$99^ICW8ElPqFt!W8yTM8Hkbe^VlJn9%)PZm!^jYyh5KH3y%E|So zC9B5eM^o)Xg1$g3vKZ2nYfirvMPBP);kN4$2*JGcX!FPfw2wvz&TYC;(slfM_>oXpXUR;rr@Y!9Y z3a5OAYQ)~DPq8k(54T!-$oO2OJt`neCjDA0?^Iv^=U#UINaxAP$^3Z#w6hW8_|PWV z$>6Ml1Cf)T+|;&;qfX@*q_dnV0^4=%yXZd&nTl?1q!s_<*&r%J5bgG2^t~I~YLz*5IF=Xt$t>u1bjKt?t1bt-ghph%3|f>D#fsC)e1X&U=%aWdzYV?fw&M;wWn z0CwFqQUVy8O^NBx&OQWmSF29fMA<`;55OS2cBQB>dp9akncuQZ zTIrDR+ilN?0y@;_4qZe{O0!eBobw4oRUZNuT>{>|8t=o=>R>ee*i05gT3{qH<40)o ziYIx+{5_SsWix6_(dGu?*)i_+`%>|Xc^n|p!uMMezfhT0D&{xhD2n(dd%XMx-Lvp! z*O-uB2?sxR2VDap7=!25^9=;ry%p+Gf+#gNNk~TYTKEM71Q4O+nu}GbXj0-4Gb)3s ze){cmh_ziA0YtBn=m1BiPWBiuUodV_Nx43*xh*Gn=rUkVT<*KXV458=-9swv2w;tE z%(`+_oAjlHf$Lhg zh}sXaPkeig6Y795^9FxtGVv2k_ZVHX+_^4{ zVQ&{!2mm}<>h1s6wq-0YvY`KBF0zjpwB>ULh47`%#lpBUB?{9=tsXvH%{@*@Q|`Nv=t(7Uili|BSM+ z;*UGKG+_u3;!p+$DsqD3k^q$G)bv=x|GelM2C_}R51IR&1Xteo=`1j-f*>$kfm7( zkI`4a&3oZ^mWkQE01Fq8s)4AHPS(r^Y9+`&|Gmhbu^#Luj>lgR zzAtQ>&5WHT9I9);7cHaUg3V=;__jf^QFu9%sbmRXA3i*$wA>B!a{Ge#zUfU2<;`c{ zv&n19DoC0Y5u6zr8EM%^!X7nUEPtxO&Bc5qCM|ujBnK3Szzvq-3O9cCrX|BZ1Ed0)bdK@+=p& zf9*IsLXyi{Oa6NxW(9?DY?SBl`u;WNVH8cyfJ}D=D{vr=^CJjlH6p!#2p}aXS=oHK z`;k)G*4Iha*-*@0uyg7(F^Q_~mD-;EWwW#wo!~aVpzO#A_sDsw1DN*BK?G1I@h(%l3kTKPn8%2ixd7jL}Zl{KHQuE zc|=A{HPss4m_fn~jOxF@Eo9waL_uvI@irEjr#V%RFN(< z506(@o*qYr^jrVBI@{YTr<{@3PzfFB zEU^Z-#f;q-dadFJIPy5h)}*CiH?`7Jvj; zuFF);NkY(o%MmV;>!*$80FW+}ExnCZ5}m#i1VJVAuo7on|0XA;LyLMruf*FSl^flw z>H*_Ci5LzXyBEzaZD|Z%*${St(P$Bp5Jx34XUxA%^|t_vNHV6m$?Z=uE=COr9?&9; z!)hT$gAHq#96H!)YJ@b%ssN;t98PH89yHqC+B&z|2BNDW*>x}Tk0*OaRA|xXL6VO7 z&$cU-5|^qzKU(GODu5eocWJz8(iqS|9Ael=v|PE;4gB6`d}v-tzE1GxwMW$5VfIOp zXThM;O)`Y6vh-)oSF0Lqmii;%fQbu#(h$rq*7mDLh!{l%4b-p60#LPAg}x~ z??!1t7-87R0PZ|+FpvFVaUXIEkg68#M>=yC7w#CGHc^s>i?U$3? zE2Xa;H-g3m0TZ4+|GHr^58V8RF8LMbWFU>u4I9-mmFN&9=NOn ztKzTC4^6fK9iI3Wi@tl7B?xDx5vzeo$aci#^g_LBX{Y>basl<2xTvTCY`Z3<$IWMz zKfa3kf%0Pqw^D%0PC?;a{9=Rlb6B(_a`h}9M>HGAzVKF&Loj)@Y#lG@gT-hFreoib zSS`C729@Gx|IKt2&*Th1Iy{d7&lr+|%nhcf4Pz3wEQIYNxU>WjO9XW6fAuB1<+`{H zHPLfQ{a&6xO(kZt>w9=&`*$V8dM{yQI>o|rq0F4yd)R|2le2tqqf;QgFItYe< zP>+{7YrH&mn|{F#>zHx^m;ShR4lCL6QcS6d@xR0CuHgfN0;o-_6fjGE4tr#5 ztWvkyj(EaFzS$580Jn@*Lj-ZIB&`%))ev+P8+I46Mo>8@ho(+8H0s(bOUg20BUUz@ zSoj`e**L7|7(Z9~^1Sc@l7HNKxBbMuJG!yEKz1f~3~kkuZkjdd?)$c}iw$1c1*55K zk*(IuaIE-E8EXMeEwEjOY(-k7^Dw8wRhfQ&^G_m00coz5&e}ex=x5mfyYCldqWho@+!#^#+T@jW6Q``ef`e2>C_5dYgO~!r-pAveJG}+ z*-;IwYnZ2 zGLpBRn%mRU)7}9AbV!)OWiUXZlGp>H%$djKmSPkr4cb~MLcEdl`g+~_r5GW~mNeeY z5!sCU!l&sa@^!P8?`hVzv(bO6;XkbRyCzl=FX`N=LbwB&EQD8r@r4Td(6&2wW4T257gdUBY+~fTBkTOH%CN z%E_7c!)&w&B-1u4o!JJUAb#oD05W+7;E0R6bzfUgBT2PiE?@BjW#sIalyhrK9&Lk= zOs0pYTRDAGkTrPN6YwK@$Xzawpj@=Ydiv;0hSwSh()u+G`w-(;zI)c%4lggSt=rq%Pws?_ zr<`n^X7bZt!oaZGW>+@b1;~6;n3IOK-Gu#;-TCVp?66{1BZez!=0iZ>4U$dXy1zd8 zR9ABt6NNMGHBdG9G9O|eSW+KTj4k+D<%JP6f@L@10h8uwvQ8!%H0RkC_=L#wIAzi8 ztspzUXpjn48au3J&#GNNnI~Bo*w!8yedAKKLWHfM^G)Qlz>BjNsn(Rv&d%j1Z5$c<5~XkQ;cRQr+uxrSImp)05xA|hGjKm< z)1#KGsQ2eYJTTw-ASNw)R=&vz)}pKyHTfzX)mlngdhq;L;A1%%rO}UGbrd7TvDn=T zgcp)dMe30tH$;m;FE>F&o#Vr6;&quo2J8YPr=G&J_xR}laNYS#yWSbtNgT$PcZzT% zU~G@eP?Bu15jtdk!h}0B_uInRq)J9#@hLcSv(e1?OXUrop9DVps@6Lap~>MR5NVkdd7O&4p}(kYh`P0cOn(N;pO zlAf_}GVtkk?*=I%avnlKEv&S9!-FUA;SY6=#Xcd%Q*7s^ug2S3beSq7DyRnjrOyw0 z()IPj=}$tF6_==W?q`*C@8}B?boo9xS6Ci47*`v=Pe5Alt+U^F+PDjdvGxxLjL)PY zP@&(yg2AO9LJ6JN+u>QBOIcL4*g^!Ek zG-j>KjiNx&EV*)6kU=})7mW1S%V}O92xmOE+4+cDiJYcrZcYt!1^+l_UH;_;bM*s~ zmO%P3`~gItR{s$=<#fa4oi!K%LE*5-Cv^#5rI)#C=A&H|2dTrEH-yMzDEUYff`tNb z#pCr^wME6j!zj>@-$RMM5tFcmvu7okx0p`c0gTB%aUBH)1jMrb)bSb{4I-D?fmx8i z>6#~JLTPi7_P*CGGOYF%Ekk&yR7-q=kgx(e#TU*e76#7+1 zDi~n_e~9cye6u;4Z8Wz55B0??+X^Lw=_ziWQ&)ni^K4!G%6%1%4Xe^c$sh?Hy|7^{J90 z(lxQ*vr`RWAfto(S`LZj76O-C8>EDo7d9oN93nX1hy%OL(l=iI-e;XC&G-&@gfqq$rEiteVR zrJ^c`RdvCM3Xym*q}e2ZG1{o{AD*HkZ??|+-Kkx67SXAJiAHz3AIWxDn})|BH@+_n zsGyp?`|w@Sae>ts$LWGh(I{gp^M%jM#5IIXhT(jVZ4o?fNUEVTUJ>){=$B2MaUlnG z@CS$A>DCQ2Izn|W)Myq*lZkSbqBD6p8Lg?ke~PN(t@Me<1)U}nv^X^?9%&p(iwq4X zm_EiEWv-e`QhakuEiNur?Ve*Wg;Csi^>R2X(!1LmP5y3^gWgB7cevgvbeXi(U}w2f zP_Oiqva4IdZ9R?Ig^D}k>uO!q8;1rjQF>OWTQZk~>QnSckeuo#P^?f*UCyTQVKHEK zVP-o9XU)YuN%YL-%O#jkZ(66ayRhE9IVoKdW!GbSy^rpT$k*lJza;fB1^3*BEKwOM zPX&`}+YnBZO1ACgM(6Ua{tK@6JEA_>j~KJ9iU-=Y_6%Cj7{_XRF4ud~ z46!lY4^Ss2^!28JIlAKjRQZ{G?Pc`3(8Usn(g+xF2sV&}P)wK?Cr8o*Et= z+ZOUx)yolx1xBQ$^Ex-IjWY1uPW^Q~tXq<;8<$fO?&;@#nA9QIFwkJJEf#EC+YGQ0 zTZjnJ4j@i*)89IOdXmEbWmIDW%Bl^*53-Oo$K<;72JWql9i@veg&K-$;X#T&mV0I@ zWXTZ5VLI~M31DL;O&QyKX|^k-Jo>zq=18QD8%>E?y(<%*nkOCj^t~Re@VfHLj;?GX z`ZA{%d8-^5*-YIRT@ryZk+h$pQfrEA^4;E1**OkacCoOmGonTn&WdH2M(mH3|Bvw=q!3zZ&0w(6Kw&?aRuQ&w! zf|6ulMXQvb&A1fmw{;xax2U!a$%MV?3e^wPY~8(LUgFex#?n>Y7 zZ0XgWq3*u0#fLWxtC>?9CW4b(uuT#{G%eL9r;25Oo2}NX#zmLjvMlk)4zp%QUiLg#Q=0+^4Rps3U{R#kCpE4P8ns!%M$*M}59_WWt9|;MVD^(42D} zcuw3PQQWD|$?Bgc-|3;C;932b3t+Wuvb$)knBaq-7DJ0ECV8l^Q2E=6X0ieXe42yt zZ<*M`m`YwJ_185Rk-T5;@NfO*>uet0#*2G|T?&2|F_IT!r~?0jjJzYG?d0s$`~`?$ zd4ZbslTX2pXe5#Li@o}Y`Mocr-fqX zG>pzxg(Jt8yV(@b6EnAYvZq!;rz(Eu_Q}!y`DReMN`{uFCZXR=)4b>(^-y7oi|Dpn z48N(FStn_Nk!rex{3Hr8Jmg@qwz;i@wL{bbqkIYV@82LVcOw|5qSt+TM#j;tBLv^= zlLZ%9+zY6P#%BZ^G)U~}rXn#AFXKJ4nN)UrJl>8akp1V1 zgx&NB;V6-qcZj;NQ8TLc;ZKAjbr)f*g`!$@mP%RNDW%VcxEeMv4XU7?H z(YmWr!F%&>gHLV)KQxx{s;M+`r%yty)`Odq`>zDASa7FL!$yZm2rXyj`^GEC=osyl zS+(w%p6Q3#+#W^BM)8CWWn}=!fCxV4B1q`RP5aK)C`eW~5gJa(_tR;v=>w`O$)cL8 zSkAx09}mmT$tmyoX_fI&6^!>|b4?`tA9!NauE%&z{~?zza4WyU;E#&HZwNNJ`oL7k z*ufMPb@VTgo%Qftqs0}#yfPvr=tG^{ze8BMTN?VOO2mkOEZ$GVC^D8oqBA@)P4!-K zi7ncS5Q{x;+}6uhhDJmEwc5D}Z{ZPeZ`z&zzOu7NJef+Jpa);NJ_P-S<{$ zBO8Xi4Gp{<7HLe>%o%ou20nmaod8FopoL$Q2PF}D89v-^ay7QmK~ z?du|?g}!R~d?AC8AWZ#Bx%z)OgNJKwgr5T`fE9EB@=p}i^6(kQ4pec&btEX{H0!Q> z>srOzEiKxFiz}f(**rO=+uJR^3AU^l9Kc{2cc~VRp zHa?;ML9VG{2cuY0FI+zp8l@SV3!EVMq^{?Xa*vGU;TmoyoQ}5DcTawNPjFD1p@5O# z*Rt~mRsx^g2-jY{53spvJbN9lc&Kl;!W^1WU)XF(527(9i=YApLD;DmfS8PcBY$IE zIx1McZ`&WsvX5on4d3ny;c~2-2mhrJA;zUU>ulETCm4z*(6bm5@;U8~_QA@HTGlQ% zE9RbPa0bw#)vK02CnD9%)T1Q(G$GNl@PYA6ol2FaSoP(`x~G4y;F|g{Ygk3D4I0dL z~#oL*;EJ70y~VUCF@-Y4tu=U6_Y7B zrpVzM+DR1U?+XdYtDzxVcs+)1zkjXX);1^li5(Az8tP}VnTsvC`|8gY99XY)(aw2x z*vN~o@*EF^T<29)=zF>Ja4gx|#jZJ4TRY$g(p12yuc}Lgta{mY+{K{CJQuOPme-!? zbZm^)Tx#OMQ@dDCv0Uj^|U2B;(w`srJQ4F^55Z*8O@x_C>a!V0k-jnOP0ln&Hyf?=qA zo-re&!wF`a4dt-`J{bunqWK|RIb;GB7e^YAhNkrUJsw!!La6CU~ z=m#ncb9AF{mk`xlpbmLm;tyUl%^QQdn(caLB_ACd&c?7X4F#x|cSRL;i|12bIFR@)}6cV}v&q`?%&X-1MsJ-hMDnME4K<3o|wqzeWF|W-iVNaUCih(r7}jw!L8Zzp_bGZoCuuJ6vb8xt@NDz*nS ztWs2XXVyT~VGR)%-+j)Ru?&L@S*ApuZ6+>-Y;1+{5+)U=x{?R?b*2TQ1o#`;}Iwxb;*XY$2jclblLeL+Guo zAFAbA;MkG=GV+huw0E@hgxu=D6FND+F|+5JnioqGu4L7J7vFQG1B3NejRo$Zg$HGV z@Yy#`9RMIV84Zl zn9DC)EnQP8z}ZU+0+zNDY{|%f8=>y$4An zW%pBs{l65XRAkOjCj}SZr^uRWfSymB@4m54eC&}#WPZ?Q(Rvpvi~rv~Wb&7xH%9|)e_vin`o6mz=Q2&=Z4hH^B1Du0fD zfQm`z*lNruR}g1?lkJ`2YHx4v?7+*Pj}H%R`ZDB8iV=PQCVTyEJdT3ZTDGABWZtCx zv;oLN_}I|}(@dp{kIIEP#$ui)+3}}QuA6Xm`qX%bc4)$0?t&;O7webXbwWf) z-H(AYfkKkH768hC&t}EikT-_x#U$_J!>F0$*OJHU2>D;Ufng1wWexuITI!RNp${b) z%xcVaIQ4>I1JT=z2ptJZ1WmXY@N&mT&RVS$TT{3*SDEu7D(|wf!Kh8&%QIf<8IdS4 zEG=HJXe6qF?GuWEjyCo&)RPkss1H5^sJz@yJ~ZoVy#VVG0y#;Y+2VE}B<1}Kan zV$@G{TezCAPI7Y>aa*hZ@tG1w^NNh7&3cJ_;e5{B^zQ{<+SqS;=a^*9|6HD3rUbD; zS`mKc3l{{WN7F%I;F3F2JBcrAo=|nPO>p2t@3b*zu9bd4KScEYMyuTv_IH z%a=qNJxJ;}t%Py6yPsOhgzt&}!)-^h&hkgV^oTB&By@CxStEoij{h?_NN*aiviA4I zJvR*~e9ma;CG=&VfFIkzf0?Bt$UcfDi?R%RZ@)kujj+(__-+zIx;n(tGDU&k&@!ef zeNjUdn3g#;a5~ilPCj*w>Z`J8NmRpZmwBGL{34hEOFPtxUX6_|z7SjEAsEiK?9@ZAC^tQDrscrO~u_ ea{YYr{36bV6e#Y^H;GI~Mp04JRH%|O5BVQoWVto~ literal 0 HcmV?d00001 diff --git a/sdformat_test_files/models/geometry_heightmap/model.config b/sdformat_test_files/models/geometry_heightmap/model.config new file mode 100644 index 00000000..fbf1bcbb --- /dev/null +++ b/sdformat_test_files/models/geometry_heightmap/model.config @@ -0,0 +1,14 @@ + + + geometry_heightmap + 1.0 + geometry_heightmap.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/geometry_mesh_collada/geometry_mesh_collada.sdf b/sdformat_test_files/models/geometry_mesh_collada/geometry_mesh_collada.sdf new file mode 100644 index 00000000..4b1fa500 --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_collada/geometry_mesh_collada.sdf @@ -0,0 +1,34 @@ + + + + + + + + model://geometry_mesh_collada/torus.dae + 0.1 0.1 0.1 + + + + + + + model://geometry_mesh_collada/torus.dae + 0.1 0.1 0.1 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/geometry_mesh_collada/model.config b/sdformat_test_files/models/geometry_mesh_collada/model.config new file mode 100644 index 00000000..7b20bc55 --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_collada/model.config @@ -0,0 +1,15 @@ + + + geometry_mesh_collada + 1.0 + geometry_mesh_collada.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + A single link using mesh geometry with a COLLADA mesh. + + diff --git a/sdformat_test_files/models/geometry_mesh_collada/torus.dae b/sdformat_test_files/models/geometry_mesh_collada/torus.dae new file mode 100644 index 00000000..d69abbe6 --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_collada/torus.dae @@ -0,0 +1,126 @@ + + + + + Blender User + Blender 2.83.3 commit date:2020-07-22, commit time:06:01, hash:353e5bd7493e + + 2020-07-30T13:30:38 + 2020-07-30T13:30:38 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + + + 0 0 0 1 + + + 0.8000001 0.002702137 0.6971079 1 + + + 0.5 + + + + + + + + + + + + + + + + + 1.25 0 0 1.216506 0 0.125 1.125 0 0.2165063 1 0 0.25 0.875 0 0.2165063 0.7834936 0 0.125 0.75 0 0 0.7834936 0 -0.125 0.875 0 -0.2165063 1 0 -0.25 1.125 0 -0.2165063 1.216506 0 -0.125 1.239306 0.1631577 0 1.206099 0.1587859 0.125 1.115375 0.1468419 0.2165063 0.9914449 0.1305261 0.25 0.8675143 0.1142104 0.2165063 0.7767907 0.1022664 0.125 0.7435837 0.0978946 0 0.7767907 0.1022664 -0.125 0.8675143 0.1142104 -0.2165063 0.9914449 0.1305261 -0.25 1.115375 0.1468419 -0.2165063 1.206099 0.1587859 -0.125 1.207407 0.3235237 0 1.175055 0.3148549 0.125 1.086667 0.2911714 0.2165063 0.9659258 0.258819 0.25 0.8451851 0.2264666 0.2165063 0.7567967 0.202783 0.125 0.7244444 0.1941142 0 0.7567967 0.202783 -0.125 0.8451851 0.2264666 -0.2165063 0.9659258 0.258819 -0.25 1.086667 0.2911714 -0.2165063 1.175055 0.3148549 -0.125 1.154849 0.4783542 0 1.123905 0.4655367 0.125 1.039364 0.4305188 0.2165063 0.9238796 0.3826833 0.25 0.8083946 0.3348479 0.2165063 0.7238538 0.29983 0.125 0.6929097 0.2870125 0 0.7238538 0.29983 -0.125 0.8083946 0.3348479 -0.2165063 0.9238796 0.3826833 -0.25 1.039364 0.4305188 -0.2165063 1.123905 0.4655367 -0.125 1.082532 0.6250001 0 1.053525 0.6082533 0.125 0.9742785 0.5625001 0.2165063 0.8660253 0.5000001 0.25 0.7577722 0.4375001 0.2165063 0.6785253 0.3917469 0.125 0.649519 0.3750001 0 0.6785253 0.3917469 -0.125 0.7577722 0.4375001 -0.2165063 0.8660253 0.5000001 -0.25 0.9742785 0.5625001 -0.2165063 1.053525 0.6082533 -0.125 0.9916918 0.7609516 0 0.9651195 0.740562 0.125 0.8925226 0.6848565 0.2165063 0.7933534 0.6087613 0.25 0.6941843 0.5326662 0.2165063 0.6215874 0.4769606 0.125 0.5950151 0.456571 0 0.6215874 0.4769606 -0.125 0.6941843 0.5326662 -0.2165063 0.7933534 0.6087613 -0.25 0.8925226 0.6848565 -0.2165063 0.9651195 0.740562 -0.125 0.8838834 0.8838835 0 0.8601998 0.8601999 0.125 0.795495 0.7954952 0.2165063 0.7071067 0.7071068 0.25 0.6187184 0.6187185 0.2165063 0.5540136 0.5540137 0.125 0.5303301 0.5303301 0 0.5540136 0.5540137 -0.125 0.6187184 0.6187185 -0.2165063 0.7071067 0.7071068 -0.25 0.795495 0.7954952 -0.2165063 0.8601998 0.8601999 -0.125 0.7609519 0.9916915 0 0.7405623 0.9651193 0.125 0.6848568 0.8925223 0.2165063 0.6087616 0.7933532 0.25 0.5326663 0.6941841 0.2165063 0.4769608 0.6215872 0.125 0.4565712 0.5950149 0 0.4769608 0.6215872 -0.125 0.5326663 0.6941841 -0.2165063 0.6087616 0.7933532 -0.25 0.6848568 0.8925223 -0.2165063 0.7405623 0.9651193 -0.125 0.625 1.082532 0 0.6082531 1.053525 0.125 0.5625 0.9742786 0.2165063 0.5 0.8660255 0.25 0.4375 0.7577723 0.2165063 0.3917468 0.6785255 0.125 0.375 0.6495191 0 0.3917468 0.6785255 -0.125 0.4375 0.7577723 -0.2165063 0.5 0.8660255 -0.25 0.5625 0.9742786 -0.2165063 0.6082531 1.053525 -0.125 0.4783546 1.154849 0 0.4655371 1.123905 0.125 0.4305191 1.039364 0.2165063 0.3826836 0.9238795 0.25 0.3348482 0.8083945 0.2165063 0.2998302 0.7238537 0.125 0.2870128 0.6929096 0 0.2998302 0.7238537 -0.125 0.3348482 0.8083945 -0.2165063 0.3826836 0.9238795 -0.25 0.4305191 1.039364 -0.2165063 0.4655371 1.123905 -0.125 0.3235238 1.207407 0 0.314855 1.175055 0.125 0.2911714 1.086667 0.2165063 0.2588191 0.9659258 0.25 0.2264667 0.8451851 0.2165063 0.2027831 0.7567967 0.125 0.1941143 0.7244444 0 0.2027831 0.7567967 -0.125 0.2264667 0.8451851 -0.2165063 0.2588191 0.9659258 -0.25 0.2911714 1.086667 -0.2165063 0.314855 1.175055 -0.125 0.1631575 1.239306 0 0.1587857 1.206099 0.125 0.1468417 1.115375 0.2165063 0.130526 0.9914449 0.25 0.1142103 0.8675143 0.2165063 0.1022663 0.7767907 0.125 0.09789448 0.7435837 0 0.1022663 0.7767907 -0.125 0.1142103 0.8675143 -0.2165063 0.130526 0.9914449 -0.25 0.1468417 1.115375 -0.2165063 0.1587857 1.206099 -0.125 0 1.25 0 0 1.216506 0.125 0 1.125 0.2165063 0 1 0.25 0 0.875 0.2165063 0 0.7834936 0.125 0 0.75 0 0 0.7834936 -0.125 0 0.875 -0.2165063 0 1 -0.25 0 1.125 -0.2165063 0 1.216506 -0.125 -0.1631579 1.239306 0 -0.1587861 1.206099 0.125 -0.1468421 1.115375 0.2165063 -0.1305263 0.9914448 0.25 -0.1142105 0.8675143 0.2165063 -0.1022665 0.7767907 0.125 -0.09789472 0.7435836 0 -0.1022665 0.7767907 -0.125 -0.1142105 0.8675143 -0.2165063 -0.1305263 0.9914448 -0.25 -0.1468421 1.115375 -0.2165063 -0.1587861 1.206099 -0.125 -0.3235237 1.207407 0 -0.3148549 1.175055 0.125 -0.2911713 1.086667 0.2165063 -0.2588189 0.9659259 0.25 -0.2264665 0.8451852 0.2165063 -0.2027829 0.7567968 0.125 -0.1941142 0.7244444 0 -0.2027829 0.7567968 -0.125 -0.2264665 0.8451852 -0.2165063 -0.2588189 0.9659259 -0.25 -0.2911713 1.086667 -0.2165063 -0.3148549 1.175055 -0.125 -0.4783544 1.154849 0 -0.4655369 1.123905 0.125 -0.4305189 1.039364 0.2165063 -0.3826835 0.9238795 0.25 -0.3348481 0.8083946 0.2165063 -0.2998301 0.7238537 0.125 -0.2870126 0.6929096 0 -0.2998301 0.7238537 -0.125 -0.3348481 0.8083946 -0.2165063 -0.3826835 0.9238795 -0.25 -0.4305189 1.039364 -0.2165063 -0.4655369 1.123905 -0.125 -0.6249998 1.082532 0 -0.608253 1.053526 0.125 -0.5624998 0.9742787 0.2165063 -0.4999998 0.8660255 0.25 -0.4374999 0.7577723 0.2165063 -0.3917467 0.6785255 0.125 -0.3749999 0.6495192 0 -0.3917467 0.6785255 -0.125 -0.4374999 0.7577723 -0.2165063 -0.4999998 0.8660255 -0.25 -0.5624998 0.9742787 -0.2165063 -0.608253 1.053526 -0.125 -0.7609518 0.9916917 0 -0.7405622 0.9651194 0.125 -0.6848566 0.8925225 0.2165063 -0.6087614 0.7933533 0.25 -0.5326663 0.6941842 0.2165063 -0.4769607 0.6215873 0.125 -0.4565711 0.595015 0 -0.4769607 0.6215873 -0.125 -0.5326663 0.6941842 -0.2165063 -0.6087614 0.7933533 -0.25 -0.6848566 0.8925225 -0.2165063 -0.7405622 0.9651194 -0.125 -0.8838837 0.8838832 0 -0.8602001 0.8601997 0.125 -0.7954953 0.7954949 0.2165063 -0.707107 0.7071066 0.25 -0.6187186 0.6187183 0.2165063 -0.5540138 0.5540135 0.125 -0.5303302 0.53033 0 -0.5540138 0.5540135 -0.125 -0.6187186 0.6187183 -0.2165063 -0.707107 0.7071066 -0.25 -0.7954953 0.7954949 -0.2165063 -0.8602001 0.8601997 -0.125 -0.9916917 0.7609518 0 -0.9651194 0.7405622 0.125 -0.8925225 0.6848566 0.2165063 -0.7933533 0.6087614 0.25 -0.6941842 0.5326663 0.2165063 -0.6215873 0.4769607 0.125 -0.595015 0.4565711 0 -0.6215873 0.4769607 -0.125 -0.6941842 0.5326663 -0.2165063 -0.7933533 0.6087614 -0.25 -0.8925225 0.6848566 -0.2165063 -0.9651194 0.7405622 -0.125 -1.082532 0.6250003 0 -1.053525 0.6082535 0.125 -0.9742785 0.5625002 0.2165063 -0.8660253 0.5000002 0.25 -0.7577721 0.4375002 0.2165063 -0.6785253 0.391747 0.125 -0.649519 0.3750002 0 -0.6785253 0.391747 -0.125 -0.7577721 0.4375002 -0.2165063 -0.8660253 0.5000002 -0.25 -0.9742785 0.5625002 -0.2165063 -1.053525 0.6082535 -0.125 -1.154849 0.4783543 0 -1.123905 0.4655369 0.125 -1.039364 0.4305189 0.2165063 -0.9238795 0.3826835 0.25 -0.8083946 0.3348481 0.2165063 -0.7238537 0.2998301 0.125 -0.6929096 0.2870126 0 -0.7238537 0.2998301 -0.125 -0.8083946 0.3348481 -0.2165063 -0.9238795 0.3826835 -0.25 -1.039364 0.4305189 -0.2165063 -1.123905 0.4655369 -0.125 -1.207407 0.3235237 0 -1.175055 0.3148549 0.125 -1.086667 0.2911713 0.2165063 -0.9659259 0.2588189 0.25 -0.8451852 0.2264665 0.2165063 -0.7567968 0.2027829 0.125 -0.7244444 0.1941142 0 -0.7567968 0.2027829 -0.125 -0.8451852 0.2264665 -0.2165063 -0.9659259 0.2588189 -0.25 -1.086667 0.2911713 -0.2165063 -1.175055 0.3148549 -0.125 -1.239306 0.1631579 0 -1.206099 0.1587861 0.125 -1.115375 0.1468421 0.2165063 -0.9914448 0.1305263 0.25 -0.8675143 0.1142105 0.2165063 -0.7767907 0.1022665 0.125 -0.7435836 0.09789472 0 -0.7767907 0.1022665 -0.125 -0.8675143 0.1142105 -0.2165063 -0.9914448 0.1305263 -0.25 -1.115375 0.1468421 -0.2165063 -1.206099 0.1587861 -0.125 -1.25 0 0 -1.216506 0 0.125 -1.125 0 0.2165063 -1 0 0.25 -0.875 0 0.2165063 -0.7834936 0 0.125 -0.75 0 0 -0.7834936 0 -0.125 -0.875 0 -0.2165063 -1 0 -0.25 -1.125 0 -0.2165063 -1.216506 0 -0.125 -1.239306 -0.1631579 0 -1.206099 -0.1587861 0.125 -1.115375 -0.1468421 0.2165063 -0.9914448 -0.1305263 0.25 -0.8675143 -0.1142105 0.2165063 -0.7767907 -0.1022665 0.125 -0.7435836 -0.09789472 0 -0.7767907 -0.1022665 -0.125 -0.8675143 -0.1142105 -0.2165063 -0.9914448 -0.1305263 -0.25 -1.115375 -0.1468421 -0.2165063 -1.206099 -0.1587861 -0.125 -1.207407 -0.3235237 0 -1.175055 -0.3148549 0.125 -1.086667 -0.2911713 0.2165063 -0.9659259 -0.2588189 0.25 -0.8451852 -0.2264665 0.2165063 -0.7567968 -0.2027829 0.125 -0.7244444 -0.1941142 0 -0.7567968 -0.2027829 -0.125 -0.8451852 -0.2264665 -0.2165063 -0.9659259 -0.2588189 -0.25 -1.086667 -0.2911713 -0.2165063 -1.175055 -0.3148549 -0.125 -1.15485 -0.4783538 0 -1.123906 -0.4655364 0.125 -1.039365 -0.4305185 0.2165063 -0.9238797 -0.382683 0.25 -0.8083947 -0.3348477 0.2165063 -0.7238538 -0.2998297 0.125 -0.6929098 -0.2870123 0 -0.7238538 -0.2998297 -0.125 -0.8083947 -0.3348477 -0.2165063 -0.9238797 -0.382683 -0.25 -1.039365 -0.4305185 -0.2165063 -1.123906 -0.4655364 -0.125 -1.082532 -0.6249998 0 -1.053526 -0.608253 0.125 -0.9742787 -0.5624998 0.2165063 -0.8660255 -0.4999998 0.25 -0.7577723 -0.4374998 0.2165063 -0.6785255 -0.3917466 0.125 -0.6495192 -0.3749999 0 -0.6785255 -0.3917466 -0.125 -0.7577723 -0.4374998 -0.2165063 -0.8660255 -0.4999998 -0.25 -0.9742787 -0.5624998 -0.2165063 -1.053526 -0.608253 -0.125 -0.9916917 -0.7609518 0 -0.9651194 -0.7405622 0.125 -0.8925225 -0.6848566 0.2165063 -0.7933533 -0.6087614 0.25 -0.6941842 -0.5326663 0.2165063 -0.6215873 -0.4769607 0.125 -0.595015 -0.4565711 0 -0.6215873 -0.4769607 -0.125 -0.6941842 -0.5326663 -0.2165063 -0.7933533 -0.6087614 -0.25 -0.8925225 -0.6848566 -0.2165063 -0.9651194 -0.7405622 -0.125 -0.8838837 -0.8838832 0 -0.8602001 -0.8601997 0.125 -0.7954953 -0.7954949 0.2165063 -0.707107 -0.7071066 0.25 -0.6187186 -0.6187183 0.2165063 -0.5540138 -0.5540135 0.125 -0.5303302 -0.53033 0 -0.5540138 -0.5540135 -0.125 -0.6187186 -0.6187183 -0.2165063 -0.707107 -0.7071066 -0.25 -0.7954953 -0.7954949 -0.2165063 -0.8602001 -0.8601997 -0.125 -0.7609523 -0.9916913 0 -0.7405627 -0.965119 0.125 -0.6848571 -0.8925222 0.2165063 -0.6087619 -0.793353 0.25 -0.5326666 -0.6941839 0.2165063 -0.476961 -0.621587 0.125 -0.4565714 -0.5950148 0 -0.476961 -0.621587 -0.125 -0.5326666 -0.6941839 -0.2165063 -0.6087619 -0.793353 -0.25 -0.6848571 -0.8925222 -0.2165063 -0.7405627 -0.965119 -0.125 -0.6249998 -1.082532 0 -0.608253 -1.053526 0.125 -0.5624998 -0.9742787 0.2165063 -0.4999998 -0.8660255 0.25 -0.4374999 -0.7577723 0.2165063 -0.3917467 -0.6785255 0.125 -0.3749999 -0.6495192 0 -0.3917467 -0.6785255 -0.125 -0.4374999 -0.7577723 -0.2165063 -0.4999998 -0.8660255 -0.25 -0.5624998 -0.9742787 -0.2165063 -0.608253 -1.053526 -0.125 -0.4783544 -1.154849 0 -0.4655369 -1.123905 0.125 -0.4305189 -1.039364 0.2165063 -0.3826835 -0.9238795 0.25 -0.3348481 -0.8083946 0.2165063 -0.2998301 -0.7238537 0.125 -0.2870126 -0.6929096 0 -0.2998301 -0.7238537 -0.125 -0.3348481 -0.8083946 -0.2165063 -0.3826835 -0.9238795 -0.25 -0.4305189 -1.039364 -0.2165063 -0.4655369 -1.123905 -0.125 -0.3235242 -1.207407 0 -0.3148554 -1.175055 0.125 -0.2911718 -1.086666 0.2165063 -0.2588194 -0.9659258 0.25 -0.2264669 -0.8451851 0.2165063 -0.2027833 -0.7567967 0.125 -0.1941145 -0.7244443 0 -0.2027833 -0.7567967 -0.125 -0.2264669 -0.8451851 -0.2165063 -0.2588194 -0.9659258 -0.25 -0.2911718 -1.086666 -0.2165063 -0.3148554 -1.175055 -0.125 -0.1631585 -1.239306 0 -0.1587867 -1.206099 0.125 -0.1468426 -1.115375 0.2165063 -0.1305268 -0.9914448 0.25 -0.1142109 -0.8675142 0.2165063 -0.1022669 -0.7767907 0.125 -0.09789508 -0.7435836 0 -0.1022669 -0.7767907 -0.125 -0.1142109 -0.8675142 -0.2165063 -0.1305268 -0.9914448 -0.25 -0.1468426 -1.115375 -0.2165063 -0.1587867 -1.206099 -0.125 0 -1.25 0 0 -1.216506 0.125 0 -1.125 0.2165063 0 -1 0.25 0 -0.875 0.2165063 0 -0.7834936 0.125 0 -0.75 0 0 -0.7834936 -0.125 0 -0.875 -0.2165063 0 -1 -0.25 0 -1.125 -0.2165063 0 -1.216506 -0.125 0.1631575 -1.239306 0 0.1587857 -1.206099 0.125 0.1468417 -1.115375 0.2165063 0.130526 -0.9914449 0.25 0.1142103 -0.8675143 0.2165063 0.1022663 -0.7767907 0.125 0.09789448 -0.7435837 0 0.1022663 -0.7767907 -0.125 0.1142103 -0.8675143 -0.2165063 0.130526 -0.9914449 -0.25 0.1468417 -1.115375 -0.2165063 0.1587857 -1.206099 -0.125 0.3235232 -1.207407 0 0.3148545 -1.175055 0.125 0.2911709 -1.086667 0.2165063 0.2588186 -0.9659259 0.25 0.2264662 -0.8451852 0.2165063 0.2027827 -0.7567968 0.125 0.1941139 -0.7244445 0 0.2027827 -0.7567968 -0.125 0.2264662 -0.8451852 -0.2165063 0.2588186 -0.9659259 -0.25 0.2911709 -1.086667 -0.2165063 0.3148545 -1.175055 -0.125 0.4783546 -1.154849 0 0.4655371 -1.123905 0.125 0.4305191 -1.039364 0.2165063 0.3826836 -0.9238795 0.25 0.3348482 -0.8083945 0.2165063 0.2998302 -0.7238537 0.125 0.2870128 -0.6929096 0 0.2998302 -0.7238537 -0.125 0.3348482 -0.8083945 -0.2165063 0.3826836 -0.9238795 -0.25 0.4305191 -1.039364 -0.2165063 0.4655371 -1.123905 -0.125 0.625 -1.082532 0 0.6082531 -1.053525 0.125 0.5625 -0.9742786 0.2165063 0.5 -0.8660255 0.25 0.4375 -0.7577723 0.2165063 0.3917468 -0.6785255 0.125 0.375 -0.6495191 0 0.3917468 -0.6785255 -0.125 0.4375 -0.7577723 -0.2165063 0.5 -0.8660255 -0.25 0.5625 -0.9742786 -0.2165063 0.6082531 -1.053525 -0.125 0.7609515 -0.9916919 0 0.7405619 -0.9651196 0.125 0.6848564 -0.8925227 0.2165063 0.6087612 -0.7933535 0.25 0.532666 -0.6941843 0.2165063 0.4769605 -0.6215874 0.125 0.4565709 -0.5950151 0 0.4769605 -0.6215874 -0.125 0.532666 -0.6941843 -0.2165063 0.6087612 -0.7933535 -0.25 0.6848564 -0.8925227 -0.2165063 0.7405619 -0.9651196 -0.125 0.883883 -0.883884 0 0.8601995 -0.8602004 0.125 0.7954947 -0.7954956 0.2165063 0.7071064 -0.7071072 0.25 0.6187181 -0.6187188 0.2165063 0.5540134 -0.554014 0.125 0.5303298 -0.5303304 0 0.5540134 -0.554014 -0.125 0.6187181 -0.6187188 -0.2165063 0.7071064 -0.7071072 -0.25 0.7954947 -0.7954956 -0.2165063 0.8601995 -0.8602004 -0.125 0.9916918 -0.7609516 0 0.9651195 -0.740562 0.125 0.8925226 -0.6848565 0.2165063 0.7933534 -0.6087613 0.25 0.6941843 -0.5326662 0.2165063 0.6215874 -0.4769606 0.125 0.5950151 -0.456571 0 0.6215874 -0.4769606 -0.125 0.6941843 -0.5326662 -0.2165063 0.7933534 -0.6087613 -0.25 0.8925226 -0.6848565 -0.2165063 0.9651195 -0.740562 -0.125 1.082532 -0.6250001 0 1.053525 -0.6082533 0.125 0.9742785 -0.5625001 0.2165063 0.8660253 -0.5000001 0.25 0.7577722 -0.4375001 0.2165063 0.6785253 -0.3917469 0.125 0.649519 -0.3750001 0 0.6785253 -0.3917469 -0.125 0.7577722 -0.4375001 -0.2165063 0.8660253 -0.5000001 -0.25 0.9742785 -0.5625001 -0.2165063 1.053525 -0.6082533 -0.125 1.154849 -0.4783548 0 1.123905 -0.4655373 0.125 1.039364 -0.4305193 0.2165063 0.9238794 -0.3826838 0.25 0.8083944 -0.3348484 0.2165063 0.7238537 -0.2998303 0.125 0.6929095 -0.2870129 0 0.7238537 -0.2998303 -0.125 0.8083944 -0.3348484 -0.2165063 0.9238794 -0.3826838 -0.25 1.039364 -0.4305193 -0.2165063 1.123905 -0.4655373 -0.125 1.207407 -0.3235235 0 1.175055 -0.3148547 0.125 1.086667 -0.2911711 0.2165063 0.9659259 -0.2588188 0.25 0.8451852 -0.2264664 0.2165063 0.7567968 -0.2027828 0.125 0.7244444 -0.194114 0 0.7567968 -0.2027828 -0.125 0.8451852 -0.2264664 -0.2165063 0.9659259 -0.2588188 -0.25 1.086667 -0.2911711 -0.2165063 1.175055 -0.3148547 -0.125 1.239306 -0.1631577 0 1.206099 -0.1587859 0.125 1.115375 -0.1468419 0.2165063 0.9914449 -0.1305261 0.25 0.8675143 -0.1142104 0.2165063 0.7767907 -0.1022664 0.125 0.7435837 -0.0978946 0 0.7767907 -0.1022664 -0.125 0.8675143 -0.1142104 -0.2165063 0.9914449 -0.1305261 -0.25 1.115375 -0.1468419 -0.2165063 1.206099 -0.1587859 -0.125 + + + + + + + + + + 0.9639959 0.06318402 0.2583018 0.7063484 0.04629641 0.7063488 0.2587817 0.01696139 0.965787 -0.258782 -0.01696157 0.9657869 -0.7063485 -0.04629641 0.7063487 -0.9639959 -0.0631833 0.2583019 -0.9639959 -0.0631833 -0.2583019 -0.7063485 -0.04629641 -0.7063487 -0.258782 -0.01696157 -0.9657869 0.2587817 0.01696139 -0.965787 0.7063484 0.04629641 -0.7063488 0.9639959 0.06318402 -0.2583018 0.9475018 0.1884695 0.2583016 0.6942628 0.1380974 0.7063486 0.254354 0.05059444 0.9657869 -0.2543538 -0.05059444 0.965787 -0.6942629 -0.1380966 0.7063487 -0.9475017 -0.18847 0.2583016 -0.9475017 -0.18847 -0.2583016 -0.6942628 -0.1380966 -0.7063487 -0.2543538 -0.05059444 -0.9657869 0.2543541 0.05059444 -0.9657869 0.6942628 0.1380974 -0.7063487 0.9475018 0.1884695 -0.2583016 0.9147959 0.3105301 0.2583014 0.670298 0.2275356 0.7063484 0.2455742 0.0833612 0.9657869 -0.2455745 -0.08336144 0.9657868 -0.6702976 -0.2275362 0.7063488 -0.9147952 -0.3105319 0.2583017 -0.9147952 -0.3105319 -0.2583018 -0.6702975 -0.2275362 -0.7063488 -0.2455745 -0.08336144 -0.9657868 0.2455741 0.0833612 -0.9657869 0.6702977 0.2275364 -0.7063485 0.9147959 0.3105301 -0.2583015 0.8664371 0.4272792 0.258301 0.6348634 0.3130809 0.706349 0.2325924 0.1147019 0.9657869 -0.2325924 -0.1147019 0.9657869 -0.6348642 -0.3130806 0.7063484 -0.8664364 -0.42728 0.258302 -0.8664364 -0.42728 -0.258302 -0.634864 -0.3130806 -0.7063485 -0.2325925 -0.1147019 -0.9657869 0.2325925 0.1147019 -0.9657869 0.6348634 0.3130809 -0.706349 0.8664371 0.4272792 -0.258301 0.8032531 0.5367164 0.258302 0.5885675 0.3932685 0.7063485 0.2156309 0.1440799 0.9657869 -0.2156307 -0.1440798 0.9657869 -0.5885678 -0.3932676 0.7063488 -0.8032532 -0.5367163 0.258302 -0.8032532 -0.5367163 -0.258302 -0.5885677 -0.3932676 -0.7063489 -0.2156307 -0.1440798 -0.9657869 0.2156307 0.1440799 -0.9657869 0.5885674 0.3932685 -0.7063486 0.8032531 0.5367164 -0.258302 0.7263252 0.6369706 0.2583025 0.5322004 0.4667274 0.7063485 0.1949796 0.170993 0.9657869 -0.1949801 -0.1709927 0.9657869 -0.5322005 -0.4667273 0.7063485 -0.7263255 -0.6369704 0.2583021 -0.7263258 -0.6369702 -0.2583019 -0.5322005 -0.4667273 -0.7063485 -0.1949802 -0.1709929 -0.9657868 0.1949796 0.170993 -0.9657869 0.5322004 0.4667274 -0.7063485 0.7263252 0.6369706 -0.2583027 0.6369706 0.7263254 0.258302 0.4667271 0.5322 0.706349 0.170993 0.19498 0.9657869 -0.1709928 -0.19498 0.9657869 -0.4667268 -0.5322005 0.7063488 -0.6369699 -0.726326 0.2583019 -0.6369699 -0.726326 -0.258302 -0.4667268 -0.5322005 -0.7063488 -0.1709929 -0.1949801 -0.9657868 0.170993 0.19498 -0.9657869 0.4667271 0.5322 -0.706349 0.6369706 0.7263255 -0.2583019 0.5367168 0.8032532 0.2583011 0.3932684 0.5885683 0.706348 0.14408 0.2156305 0.965787 -0.1440799 -0.2156304 0.965787 -0.393269 -0.5885671 0.7063487 -0.5367166 -0.8032531 0.2583016 -0.5367166 -0.8032531 -0.2583014 -0.393269 -0.5885671 -0.7063487 -0.1440797 -0.2156304 -0.965787 0.14408 0.2156305 -0.965787 0.3932685 0.5885684 -0.7063478 0.5367167 0.8032531 -0.2583019 0.4272795 0.8664369 0.2583009 0.3130804 0.634864 0.7063487 0.1147015 0.2325921 0.9657871 -0.114702 -0.2325924 0.9657869 -0.3130802 -0.6348643 0.7063485 -0.4272792 -0.8664371 0.258301 -0.4272791 -0.866437 -0.258301 -0.3130801 -0.634864 -0.7063487 -0.114702 -0.2325924 -0.9657869 0.1147015 0.232592 -0.965787 0.3130804 0.634864 -0.7063487 0.4272793 0.8664365 -0.2583026 0.3105311 0.9147952 0.2583028 0.2275359 0.6702976 0.7063489 0.08336138 0.2455747 0.9657868 -0.08336138 -0.245574 0.9657869 -0.2275356 -0.6702978 0.7063487 -0.3105311 -0.9147953 0.2583019 -0.3105312 -0.9147954 -0.2583021 -0.2275355 -0.6702977 -0.7063488 -0.0833612 -0.2455741 -0.9657869 0.08336132 0.2455745 -0.9657868 0.2275357 0.6702976 -0.7063489 0.3105312 0.9147953 -0.2583022 0.1884698 0.9475013 0.2583029 0.1380973 0.6942626 0.7063488 0.05059427 0.2543538 0.9657869 -0.05059409 -0.2543538 0.965787 -0.1380971 -0.6942626 0.7063489 -0.1884697 -0.947502 0.2583006 -0.1884697 -0.9475019 -0.2583011 -0.1380971 -0.6942625 -0.706349 -0.05059409 -0.2543538 -0.965787 0.05059421 0.2543544 -0.9657868 0.1380972 0.6942628 -0.7063486 0.1884698 0.9475013 -0.2583035 0.06318366 0.9639962 0.2583007 0.04629635 0.7063482 0.706349 0.01696121 0.2587815 0.965787 -0.01696157 -0.2587817 0.9657869 -0.04629671 -0.7063483 0.7063488 -0.06318378 -0.9639961 0.2583014 -0.06318342 -0.9639959 -0.258302 -0.04629671 -0.7063484 -0.7063487 -0.01696157 -0.2587817 -0.9657869 0.01696127 0.2587813 -0.9657871 0.04629629 0.7063487 -0.7063484 0.06318342 0.9639961 -0.258301 -0.06318414 0.9639962 0.2583006 -0.04629671 0.706349 0.7063482 -0.01696139 0.2587817 0.965787 0.01696151 -0.2587814 0.9657871 0.04629641 -0.7063484 0.7063488 0.06318354 -0.9639962 0.2583009 0.06318378 -0.9639962 -0.2583003 0.04629641 -0.7063482 -0.7063489 0.01696151 -0.2587814 -0.965787 -0.01696145 0.2587818 -0.9657869 -0.04629671 0.7063494 -0.7063478 -0.06318414 0.9639962 -0.2583009 -0.1884692 0.9475021 0.2583008 -0.1380972 0.694262 0.7063494 -0.05059391 0.2543542 0.9657868 0.05059385 -0.2543539 0.9657869 0.1380973 -0.6942631 0.7063484 0.1884698 -0.9475018 0.2583013 0.1884698 -0.9475019 -0.258301 0.1380972 -0.6942629 -0.7063486 0.05059379 -0.254354 -0.9657869 -0.05059391 0.2543542 -0.9657868 -0.1380973 0.6942623 -0.7063491 -0.1884692 0.9475022 -0.2583005 -0.3105313 0.9147959 0.2582997 -0.2275357 0.6702976 0.7063488 -0.08336132 0.2455739 0.965787 0.08336126 -0.2455744 0.9657868 0.2275355 -0.6702976 0.706349 0.3105313 -0.9147956 0.2583011 0.3105313 -0.9147956 -0.2583011 0.2275356 -0.6702977 -0.7063488 0.08336132 -0.2455744 -0.9657868 -0.08336132 0.2455739 -0.965787 -0.2275358 0.6702979 -0.7063486 -0.3105313 0.9147951 -0.2583027 -0.4272789 0.8664364 0.2583039 -0.3130802 0.6348643 0.7063485 -0.1147018 0.2325921 0.9657869 0.1147016 -0.2325924 0.9657869 0.3130804 -0.6348643 0.7063484 0.4272791 -0.8664368 0.2583017 0.4272791 -0.8664368 -0.2583018 0.3130803 -0.6348641 -0.7063487 0.1147016 -0.2325924 -0.9657869 -0.1147019 0.2325922 -0.965787 -0.3130805 0.6348643 -0.7063484 -0.4272787 0.8664367 -0.2583029 -0.536717 0.8032532 0.2583005 -0.3932684 0.5885676 0.7063484 -0.1440805 0.2156313 0.9657867 0.1440801 -0.2156308 0.9657869 0.393268 -0.5885673 0.706349 0.5367168 -0.8032528 0.2583023 0.5367168 -0.8032528 -0.258302 0.393268 -0.5885673 -0.706349 0.1440798 -0.2156308 -0.9657869 -0.1440804 0.2156312 -0.9657868 -0.3932684 0.5885676 -0.7063484 -0.5367169 0.8032532 -0.2583008 -0.6369705 0.7263256 0.2583019 -0.4667272 0.5322008 0.7063484 -0.1709928 0.1949799 0.965787 0.1709929 -0.19498 0.9657869 0.4667274 -0.5322003 0.7063486 0.6369709 -0.7263253 0.2583018 0.6369709 -0.7263253 -0.2583016 0.4667274 -0.5322003 -0.7063486 0.1709928 -0.1949799 -0.965787 -0.1709928 0.1949799 -0.965787 -0.466727 0.5322005 -0.7063488 -0.6369705 0.7263257 -0.2583015 -0.7263259 0.63697 0.2583021 -0.5322001 0.4667264 0.7063495 -0.1949803 0.1709927 0.9657868 0.19498 -0.170993 0.9657869 0.5322001 -0.4667273 0.7063488 0.7263252 -0.6369708 0.2583019 0.7263253 -0.6369709 -0.2583016 0.5322001 -0.4667273 -0.7063488 0.19498 -0.170993 -0.9657869 -0.1949803 0.1709927 -0.9657868 -0.5322001 0.4667264 -0.7063495 -0.726326 0.6369701 -0.2583018 -0.8032531 0.5367167 0.2583014 -0.5885676 0.3932688 0.7063483 -0.2156313 0.1440802 0.9657868 0.2156303 -0.14408 0.965787 0.5885676 -0.393268 0.7063487 0.8032533 -0.5367162 0.258302 0.8032533 -0.5367162 -0.258302 0.5885676 -0.393268 -0.7063487 0.2156305 -0.14408 -0.9657869 -0.2156312 0.1440801 -0.9657868 -0.5885675 0.3932689 -0.7063484 -0.8032532 0.5367168 -0.2583016 -0.8664368 0.4272789 0.2583022 -0.634864 0.3130804 0.7063487 -0.2325921 0.114702 0.9657869 0.2325922 -0.1147019 0.9657869 0.6348637 -0.3130804 0.7063489 0.8664365 -0.42728 0.2583016 0.8664365 -0.42728 -0.2583016 0.6348637 -0.3130806 -0.7063487 0.2325923 -0.1147019 -0.9657869 -0.2325921 0.114702 -0.9657869 -0.634864 0.3130804 -0.7063487 -0.8664368 0.4272789 -0.2583022 -0.9147954 0.3105311 0.258302 -0.6702979 0.2275346 0.7063488 -0.2455744 0.08336156 0.9657868 0.2455739 -0.0833612 0.9657869 0.6702978 -0.2275359 0.7063485 0.9147953 -0.3105314 0.258302 0.9147953 -0.3105314 -0.2583019 0.6702978 -0.2275359 -0.7063486 0.2455739 -0.0833612 -0.965787 -0.245574 0.0833612 -0.9657869 -0.6702979 0.2275346 -0.7063489 -0.9147951 0.3105322 -0.2583019 -0.947502 0.1884685 0.2583016 -0.6942624 0.1380975 0.706349 -0.2543543 0.05059379 0.9657868 0.2543539 -0.05059409 0.9657869 0.6942627 -0.1380969 0.7063487 0.9475018 -0.1884691 0.258302 0.9475018 -0.1884691 -0.2583019 0.6942628 -0.1380969 -0.7063487 0.2543539 -0.05059409 -0.9657869 -0.2543544 0.05059379 -0.9657868 -0.6942624 0.1380975 -0.706349 -0.947502 0.1884685 -0.2583016 -0.963996 0.06318402 0.2583016 -0.7063485 0.0462979 0.7063486 -0.2587817 0.01696181 0.9657869 0.2587817 -0.01696157 0.965787 0.7063485 -0.04629635 0.7063487 0.9639959 -0.0631836 0.258302 0.9639958 -0.06318444 -0.258302 0.7063485 -0.04629635 -0.7063487 0.258782 -0.01696133 -0.9657869 -0.2587816 0.01696181 -0.9657869 -0.7063485 0.0462979 -0.7063486 -0.963996 0.06318402 -0.2583016 -0.9639958 -0.06318414 0.2583018 -0.7063487 -0.04629677 0.7063485 -0.2587819 -0.01696121 0.9657869 0.2587818 0.01696181 0.9657869 0.7063486 0.04629671 0.7063486 0.9639959 0.06318354 0.2583018 0.9639958 0.06318432 -0.2583018 0.7063486 0.04629671 -0.7063485 0.2587819 0.01696181 -0.9657869 -0.258782 -0.01696121 -0.9657869 -0.7063487 -0.04629677 -0.7063485 -0.9639958 -0.06318414 -0.2583018 -0.9475018 -0.1884698 0.2583014 -0.6942628 -0.138096 0.7063489 -0.2543538 -0.05059409 0.9657869 0.2543543 0.05059403 0.9657869 0.6942628 0.1380978 0.7063486 0.9475017 0.1884692 0.258302 0.9475017 0.1884692 -0.258302 0.6942628 0.1380978 -0.7063485 0.2543542 0.05059403 -0.9657869 -0.2543539 -0.05059409 -0.9657869 -0.6942628 -0.138096 -0.7063489 -0.9475017 -0.1884698 -0.2583014 -0.9147952 -0.3105322 0.2583014 -0.6702978 -0.2275352 0.7063489 -0.2455739 -0.0833615 0.9657869 0.2455741 0.08336102 0.9657869 0.6702978 0.2275355 0.7063487 0.9147952 0.3105317 0.2583019 0.9147952 0.3105317 -0.2583019 0.6702977 0.2275355 -0.7063488 0.2455741 0.08336102 -0.9657869 -0.2455739 -0.08336144 -0.9657869 -0.6702978 -0.2275353 -0.7063489 -0.9147953 -0.3105319 -0.2583013 -0.8664371 -0.4272785 0.258302 -0.6348643 -0.3130799 0.7063485 -0.2325925 -0.1147021 0.9657869 0.2325925 0.1147017 0.9657869 0.6348638 0.3130795 0.7063492 0.8664374 0.4272781 0.2583013 0.8664374 0.4272781 -0.2583013 0.6348639 0.3130795 -0.7063491 0.2325925 0.1147015 -0.9657869 -0.2325925 -0.1147021 -0.9657869 -0.6348643 -0.3130799 -0.7063487 -0.8664371 -0.4272785 -0.258302 -0.8032534 -0.5367161 0.2583019 -0.5885673 -0.3932692 0.7063483 -0.2156307 -0.1440798 0.965787 0.2156307 0.1440801 0.9657869 0.5885679 0.3932684 0.7063483 0.8032531 0.5367168 0.2583014 0.8032531 0.5367168 -0.2583014 0.5885677 0.3932682 -0.7063484 0.2156309 0.1440799 -0.9657869 -0.2156307 -0.1440798 -0.965787 -0.5885673 -0.3932692 -0.7063483 -0.8032534 -0.5367161 -0.2583019 -0.7263261 -0.6369701 0.2583013 -0.5322009 -0.466727 0.7063484 -0.1949796 -0.1709928 0.965787 0.1949801 0.1709929 0.9657868 0.5322002 0.466727 0.706349 0.7263253 0.6369709 0.2583014 0.7263253 0.6369709 -0.2583014 0.5322 0.4667268 -0.7063493 0.1949802 0.170993 -0.9657869 -0.1949796 -0.1709928 -0.965787 -0.5322009 -0.466727 -0.7063484 -0.7263262 -0.6369701 -0.2583011 -0.6369705 -0.7263255 0.2583019 -0.4667276 -0.5322003 0.7063486 -0.1709932 -0.1949803 0.9657867 0.1709932 0.19498 0.9657869 0.4667277 0.5321999 0.7063488 0.6369712 0.726325 0.2583018 0.6369712 0.7263249 -0.258302 0.4667277 0.5321999 -0.7063488 0.1709932 0.19498 -0.9657868 -0.170993 -0.1949803 -0.9657868 -0.4667276 -0.5322003 -0.7063485 -0.6369708 -0.7263256 -0.2583011 -0.5367169 -0.8032531 0.2583016 -0.3932686 -0.5885677 0.7063483 -0.1440799 -0.2156308 0.965787 0.1440803 0.2156311 0.9657868 0.3932682 0.5885672 0.7063489 0.5367166 0.8032534 0.2583012 0.5367166 0.8032534 -0.2583012 0.3932682 0.5885672 -0.7063489 0.1440802 0.2156311 -0.9657868 -0.1440799 -0.2156308 -0.965787 -0.3932683 -0.5885681 -0.7063482 -0.5367169 -0.8032531 -0.2583013 -0.4272794 -0.8664366 0.2583022 -0.3130804 -0.6348645 0.7063481 -0.1147018 -0.2325924 0.9657869 0.1147019 0.2325925 0.9657869 0.3130803 0.6348643 0.7063485 0.4272792 0.8664366 0.2583022 0.4272793 0.8664367 -0.2583019 0.3130802 0.634864 -0.7063487 0.1147019 0.2325925 -0.9657869 -0.1147018 -0.2325924 -0.9657869 -0.3130807 -0.6348646 -0.706348 -0.4272792 -0.866437 -0.2583011 -0.3105313 -0.9147956 0.2583007 -0.2275357 -0.6702982 0.7063482 -0.08336114 -0.2455739 0.9657869 0.08336132 0.2455742 0.9657869 0.2275357 0.6702981 0.7063483 0.3105312 0.9147953 0.2583023 0.3105318 0.9147953 -0.2583018 0.2275357 0.6702981 -0.7063483 0.08336132 0.2455742 -0.9657869 -0.08336108 -0.245574 -0.965787 -0.2275357 -0.6702981 -0.7063484 -0.3105313 -0.9147956 -0.2583012 -0.1884704 -0.9475011 0.2583034 -0.1380981 -0.6942632 0.7063481 -0.05059438 -0.2543542 0.9657868 0.05059432 0.2543542 0.9657868 0.1380978 0.6942629 0.7063484 0.1884704 0.9475017 0.2583016 0.1884704 0.9475015 -0.258302 0.1380979 0.6942631 -0.7063482 0.05059432 0.2543542 -0.9657868 -0.05059409 -0.254354 -0.9657869 -0.1380978 -0.6942631 -0.7063482 -0.1884704 -0.9475011 -0.2583034 -0.0631839 -0.9639964 0.2582999 -0.04629659 -0.7063484 0.7063487 -0.01696133 -0.2587818 0.9657869 0.01696151 0.258782 0.9657869 0.04629665 0.7063488 0.7063484 0.06318414 0.9639962 0.2583008 0.06318414 0.9639961 -0.258301 0.04629671 0.7063488 -0.7063484 0.01696145 0.2587819 -0.9657869 -0.01696151 -0.2587815 -0.9657871 -0.04629659 -0.7063484 -0.7063487 -0.06318366 -0.963996 -0.2583016 0.06318366 -0.9639962 0.2583007 0.04629623 -0.7063477 0.7063495 0.01696139 -0.258782 0.9657868 -0.01696139 0.2587818 0.9657869 -0.04629671 0.7063487 0.7063485 -0.06318378 0.9639961 0.2583012 -0.06318342 0.9639959 -0.2583018 -0.04629659 0.7063485 -0.7063487 -0.01696139 0.2587818 -0.9657869 0.01696145 -0.2587822 -0.9657868 0.04629623 -0.7063483 -0.706349 0.06318342 -0.9639961 -0.258301 0.1884691 -0.9475018 0.2583014 0.1380975 -0.6942629 0.7063484 0.05059421 -0.2543544 0.9657868 -0.05059397 0.2543544 0.9657868 -0.1380971 0.6942629 0.7063485 -0.1884692 0.9475019 0.2583015 -0.1884697 0.9475015 -0.2583022 -0.138097 0.6942628 -0.7063487 -0.05059397 0.2543544 -0.9657868 0.05059421 -0.2543542 -0.9657868 0.1380975 -0.6942631 -0.7063483 0.1884698 -0.947502 -0.2583004 0.3105313 -0.9147955 0.2583014 0.2275352 -0.6702972 0.7063494 0.08336126 -0.2455743 0.9657869 -0.08336132 0.2455742 0.9657868 -0.227535 0.6702977 0.706349 -0.3105308 0.9147956 0.2583019 -0.3105308 0.9147956 -0.2583014 -0.2275355 0.6702976 -0.7063489 -0.08336144 0.2455742 -0.9657868 0.08336073 -0.2455738 -0.9657871 0.2275352 -0.6702972 -0.7063494 0.3105314 -0.9147955 -0.2583012 0.4272794 -0.8664373 0.2582998 0.3130801 -0.6348642 0.7063487 0.114702 -0.2325925 0.9657868 -0.1147016 0.2325923 0.9657869 -0.31308 0.6348636 0.7063493 -0.4272795 0.8664365 0.2583022 -0.4272795 0.8664365 -0.2583023 -0.31308 0.6348637 -0.7063491 -0.1147016 0.2325923 -0.9657869 0.1147019 -0.2325924 -0.9657869 0.3130803 -0.6348645 -0.7063483 0.4272792 -0.8664368 -0.2583015 0.5367167 -0.8032534 0.2583007 0.3932682 -0.5885675 0.7063487 0.14408 -0.2156309 0.9657869 -0.1440799 0.2156308 0.9657869 -0.3932684 0.588568 0.7063482 -0.5367169 0.8032528 0.258302 -0.536717 0.8032529 -0.2583019 -0.3932682 0.5885678 -0.7063484 -0.1440796 0.2156308 -0.965787 0.1440798 -0.2156308 -0.965787 0.3932685 -0.5885679 -0.7063483 0.5367166 -0.8032533 -0.258301 0.6369698 -0.7263261 0.258302 0.466727 -0.5322009 0.7063485 0.1709925 -0.1949802 0.9657869 -0.1709925 0.1949798 0.965787 -0.4667266 0.5322014 0.7063484 -0.6369695 0.7263266 0.2583015 -0.6369695 0.7263265 -0.2583017 -0.4667266 0.5322014 -0.7063484 -0.1709925 0.1949798 -0.965787 0.1709925 -0.1949802 -0.9657869 0.4667268 -0.532201 -0.7063484 0.6369699 -0.7263261 -0.2583019 0.7263257 -0.6369704 0.2583017 0.5322011 -0.4667276 0.706348 0.19498 -0.1709926 0.9657869 -0.19498 0.170993 0.9657869 -0.5322005 0.4667272 0.7063486 -0.726326 0.6369702 0.2583014 -0.7263259 0.6369701 -0.2583016 -0.5322005 0.4667273 -0.7063487 -0.1949801 0.170993 -0.9657869 0.19498 -0.1709925 -0.965787 0.5322011 -0.4667276 -0.706348 0.7263257 -0.6369704 -0.2583015 0.8032534 -0.5367159 0.2583022 0.5885679 -0.3932682 0.7063484 0.2156312 -0.1440798 0.9657869 -0.2156308 0.14408 0.9657869 -0.5885676 0.3932687 0.7063484 -0.8032531 0.5367165 0.2583018 -0.8032531 0.5367165 -0.2583019 -0.5885674 0.3932686 -0.7063486 -0.2156308 0.1440799 -0.9657869 0.215631 -0.1440798 -0.9657869 0.5885679 -0.3932682 -0.7063484 0.8032534 -0.5367159 -0.2583023 0.8664361 -0.4272803 0.258302 0.6348637 -0.3130808 0.7063488 0.2325921 -0.1147015 0.9657871 -0.2325923 0.1147021 0.9657869 -0.6348642 0.3130809 0.7063482 -0.8664362 0.4272804 0.2583021 -0.8664362 0.4272804 -0.2583021 -0.6348637 0.3130817 -0.7063484 -0.2325923 0.1147021 -0.9657869 0.2325921 -0.1147015 -0.9657871 0.6348636 -0.3130808 -0.7063488 0.8664361 -0.4272803 -0.2583022 0.9147953 -0.3105314 0.2583019 0.670298 -0.2275352 0.7063486 0.2455741 -0.0833612 0.9657869 -0.2455742 0.08336138 0.9657869 -0.670298 0.227536 0.7063483 -0.9147955 0.3105307 0.2583019 -0.9147955 0.3105307 -0.2583019 -0.670298 0.227536 -0.7063484 -0.2455739 0.08336114 -0.9657869 0.2455739 -0.0833612 -0.965787 0.670298 -0.2275345 -0.7063488 0.9147953 -0.3105314 -0.2583019 0.947502 -0.1884685 0.2583016 0.6942623 -0.1380975 0.706349 0.2543541 -0.05059367 0.9657869 -0.2543542 0.05059403 0.9657868 -0.6942628 0.1380977 0.7063485 -0.9475015 0.1884703 0.2583019 -0.9475015 0.1884703 -0.258302 -0.6942628 0.1380978 -0.7063485 -0.2543543 0.05059403 -0.9657869 0.254354 -0.05059367 -0.9657869 0.6942623 -0.1380975 -0.7063491 0.9475018 -0.1884698 -0.2583015 0.9639959 -0.0631842 0.2583016 0.7063486 -0.04629683 0.7063485 0.2587819 -0.01696121 0.9657869 -0.2587817 0.01696115 0.9657869 -0.7063485 0.04629683 0.7063487 -0.9639959 0.06318366 0.2583016 -0.9639959 0.06318366 -0.2583016 -0.7063485 0.04629683 -0.7063487 -0.2587817 0.01696115 -0.965787 0.258782 -0.01696121 -0.9657869 0.7063486 -0.04629683 -0.7063486 0.9639959 -0.0631842 -0.2583016 0.9639959 0.0631842 0.2583016 0.7063486 0.04629683 0.7063485 0.2587819 0.01696121 0.9657869 -0.2587817 -0.01696115 0.9657869 -0.7063485 -0.04629683 0.7063487 -0.9639959 -0.06318366 0.2583016 -0.9639959 -0.06318366 -0.2583016 -0.7063485 -0.04629683 -0.7063487 -0.2587817 -0.01696115 -0.965787 0.258782 0.01696121 -0.9657869 0.7063486 0.04629683 -0.7063486 0.9639959 0.0631842 -0.2583016 0.9475015 0.1884709 0.2583016 0.694263 0.1380974 0.7063484 0.254354 0.05059397 0.9657869 -0.2543541 -0.05059391 0.9657868 -0.6942626 -0.1380975 0.7063487 -0.9475017 -0.18847 0.2583015 -0.9475017 -0.18847 -0.2583015 -0.6942626 -0.1380975 -0.7063487 -0.2543542 -0.05059397 -0.9657869 0.2543539 0.05059397 -0.9657869 0.694263 0.1380974 -0.7063484 0.9475015 0.1884709 -0.2583015 0.9147955 0.3105317 0.2583012 0.6702975 0.2275348 0.7063493 0.2455741 0.08336132 0.9657869 -0.2455738 -0.08336102 0.9657869 -0.6702981 -0.2275352 0.7063485 -0.9147957 -0.3105303 0.2583018 -0.9147957 -0.3105303 -0.2583018 -0.6702981 -0.2275352 -0.7063485 -0.2455739 -0.08336108 -0.965787 0.245574 0.08336132 -0.9657869 0.6702978 0.2275341 -0.7063491 0.9147955 0.3105317 -0.2583012 0.8664364 0.4272797 0.2583022 0.6348642 0.3130798 0.7063488 0.2325925 0.1147015 0.9657869 -0.2325921 -0.1147019 0.965787 -0.6348641 -0.3130807 0.7063484 -0.8664367 -0.4272789 0.2583024 -0.8664368 -0.427279 -0.2583023 -0.634864 -0.3130806 -0.7063485 -0.2325922 -0.1147019 -0.9657869 0.2325925 0.1147015 -0.9657869 0.6348641 0.3130798 -0.7063489 0.8664364 0.4272797 -0.2583022 0.8032534 0.5367159 0.2583022 0.5885679 0.3932682 0.7063484 0.2156311 0.1440798 0.9657869 -0.2156308 -0.14408 0.9657869 -0.5885676 -0.3932687 0.7063484 -0.8032531 -0.5367165 0.2583018 -0.8032531 -0.5367165 -0.2583019 -0.5885674 -0.3932686 -0.7063486 -0.2156308 -0.1440799 -0.9657869 0.2156312 0.1440798 -0.9657869 0.5885679 0.3932682 -0.7063484 0.8032534 0.5367159 -0.2583023 0.7263256 0.6369707 0.2583012 0.5322003 0.466728 0.7063483 0.19498 0.1709929 0.9657869 -0.1949801 -0.1709926 0.9657869 -0.5322005 -0.466727 0.7063487 -0.7263258 -0.6369702 0.2583017 -0.7263255 -0.6369705 -0.258302 -0.5322005 -0.466727 -0.7063487 -0.1949801 -0.1709926 -0.9657869 0.1949799 0.1709928 -0.965787 0.5322003 0.466728 -0.7063483 0.7263256 0.6369707 -0.2583014 0.6369702 0.7263259 0.2583017 0.4667276 0.5322002 0.7063486 0.1709925 0.19498 0.9657869 -0.1709927 -0.19498 0.9657869 -0.4667269 -0.5322005 0.7063488 -0.6369708 -0.7263255 0.2583015 -0.6369707 -0.7263254 -0.2583018 -0.4667269 -0.5322005 -0.7063488 -0.1709927 -0.19498 -0.9657869 0.1709925 0.19498 -0.9657869 0.4667277 0.5322004 -0.7063484 0.6369702 0.7263259 -0.2583017 0.5367173 0.8032531 0.2583004 0.3932679 0.5885666 0.7063497 0.1440802 0.215631 0.9657869 -0.1440802 -0.2156313 0.9657868 -0.3932687 -0.5885678 0.7063482 -0.5367173 -0.8032528 0.2583016 -0.5367173 -0.8032528 -0.2583015 -0.3932688 -0.588568 -0.7063479 -0.1440802 -0.2156313 -0.9657868 0.1440801 0.2156309 -0.9657869 0.3932681 0.5885668 -0.7063493 0.5367172 0.803253 -0.2583007 0.4272791 0.8664367 0.2583021 0.3130801 0.6348642 0.7063487 0.114702 0.2325925 0.9657868 -0.1147016 -0.2325923 0.9657869 -0.31308 -0.6348636 0.7063493 -0.4272795 -0.8664365 0.2583022 -0.4272795 -0.8664365 -0.2583023 -0.31308 -0.6348637 -0.7063491 -0.1147016 -0.2325923 -0.9657869 0.1147019 0.2325924 -0.9657869 0.3130803 0.6348645 -0.7063483 0.4272793 0.8664373 -0.2583004 0.3105316 0.9147958 0.2582998 0.2275357 0.6702978 0.7063487 0.08336108 0.2455735 0.9657871 -0.08336097 -0.2455741 0.9657869 -0.2275356 -0.670298 0.7063484 -0.3105312 -0.9147955 0.2583016 -0.3105312 -0.9147955 -0.2583015 -0.2275358 -0.6702982 -0.7063483 -0.08336114 -0.2455741 -0.965787 0.08336102 0.2455734 -0.9657871 0.2275358 0.6702979 -0.7063485 0.3105316 0.9147957 -0.2583004 0.1884698 0.9475018 0.2583012 0.1380974 0.6942628 0.7063486 0.05059427 0.2543546 0.9657868 -0.05059397 -0.2543541 0.9657869 -0.1380973 -0.6942626 0.7063488 -0.1884696 -0.9475014 0.2583029 -0.1884696 -0.9475015 -0.2583024 -0.1380972 -0.6942625 -0.706349 -0.05059409 -0.2543541 -0.9657869 0.05059415 0.2543535 -0.965787 0.1380975 0.6942629 -0.7063485 0.1884698 0.9475019 -0.2583009 0.06318342 0.9639962 0.2583007 0.04629617 0.7063479 0.7063493 0.01696139 0.258782 0.9657868 -0.01696139 -0.2587818 0.9657869 -0.04629671 -0.7063487 0.7063485 -0.06318342 -0.963996 0.2583015 -0.06318378 -0.9639962 -0.2583009 -0.04629659 -0.7063485 -0.7063487 -0.01696139 -0.2587818 -0.9657869 0.01696145 0.2587822 -0.9657868 0.04629623 0.7063474 -0.7063499 0.06318366 0.9639963 -0.2583004 -0.0631839 0.9639957 0.2583026 -0.04629677 0.7063491 0.706348 -0.01696157 0.2587816 0.965787 0.01696133 -0.2587823 0.9657868 0.04629653 -0.7063485 0.7063487 0.06318378 -0.9639959 0.2583017 0.06318354 -0.9639958 -0.2583021 0.04629653 -0.7063483 -0.7063489 0.01696133 -0.2587822 -0.9657868 -0.01696157 0.2587818 -0.965787 -0.04629671 0.7063488 -0.7063484 -0.0631839 0.9639956 -0.2583028 -0.1884691 0.9475015 0.2583028 -0.1380968 0.6942626 0.706349 -0.05059409 0.2543538 0.965787 0.05059432 -0.254354 0.9657869 0.1380974 -0.6942622 0.7063492 0.1884697 -0.9475018 0.2583015 0.1884697 -0.9475018 -0.2583014 0.1380973 -0.6942621 -0.7063493 0.05059432 -0.254354 -0.9657869 -0.05059415 0.2543538 -0.965787 -0.1380968 0.6942624 -0.7063491 -0.1884691 0.9475014 -0.2583031 -0.3105314 0.9147948 0.2583039 -0.2275352 0.6702978 0.7063487 -0.08336102 0.2455744 0.9657869 0.0833612 -0.2455741 0.9657869 0.2275356 -0.6702978 0.7063487 0.3105312 -0.9147955 0.2583016 0.3105312 -0.9147954 -0.258302 0.2275356 -0.6702978 -0.7063487 0.0833612 -0.2455741 -0.9657869 -0.08336102 0.2455745 -0.9657868 -0.2275352 0.670298 -0.7063486 -0.3105313 0.9147956 -0.2583009 -0.4272792 0.8664371 0.2583008 -0.3130807 0.6348646 0.706348 -0.1147018 0.2325924 0.9657869 0.1147019 -0.2325925 0.9657869 0.3130803 -0.6348643 0.7063485 0.4272792 -0.8664366 0.2583022 0.4272793 -0.8664367 -0.2583019 0.3130802 -0.634864 -0.7063487 0.1147019 -0.2325925 -0.9657869 -0.1147018 0.2325924 -0.9657869 -0.3130806 0.6348649 -0.7063478 -0.4272794 0.8664367 -0.2583019 -0.5367166 0.8032529 0.2583025 -0.3932683 0.588567 0.7063491 -0.1440797 0.2156303 0.9657871 0.1440799 -0.2156311 0.9657869 0.3932684 -0.5885675 0.7063486 0.5367165 -0.8032532 0.2583015 0.5367165 -0.8032532 -0.2583016 0.3932684 -0.5885675 -0.7063486 0.1440801 -0.2156312 -0.9657868 -0.1440797 0.2156303 -0.9657871 -0.3932681 0.5885668 -0.7063493 -0.5367165 0.8032529 -0.2583029 -0.6369704 0.7263257 0.2583017 -0.466727 0.5322005 0.7063488 -0.1709929 0.1949802 0.9657869 0.170993 -0.1949795 0.965787 0.4667272 -0.5322002 0.7063489 0.6369708 -0.7263254 0.2583016 0.6369708 -0.7263254 -0.2583016 0.4667272 -0.5322002 -0.7063489 0.170993 -0.1949794 -0.9657871 -0.1709929 0.1949802 -0.9657869 -0.4667271 0.5322007 -0.7063486 -0.6369704 0.7263256 -0.258302 -0.7263261 0.6369701 0.2583013 -0.5322009 0.466727 0.7063484 -0.1949796 0.1709928 0.965787 0.1949801 -0.1709929 0.9657868 0.5322002 -0.466727 0.706349 0.7263253 -0.6369709 0.2583014 0.7263253 -0.6369709 -0.2583014 0.5322 -0.4667268 -0.7063493 0.1949802 -0.170993 -0.9657869 -0.1949796 0.1709928 -0.965787 -0.5322009 0.466727 -0.7063484 -0.7263262 0.6369701 -0.2583011 -0.8032524 0.5367175 0.2583019 -0.5885672 0.3932682 0.706349 -0.2156308 0.1440799 0.9657869 0.2156311 -0.1440799 0.9657869 0.5885678 -0.3932685 0.7063482 0.8032531 -0.5367165 0.2583018 0.8032531 -0.5367165 -0.2583018 0.5885678 -0.3932686 -0.7063482 0.2156309 -0.1440799 -0.9657869 -0.2156307 0.1440798 -0.9657869 -0.5885671 0.3932682 -0.706349 -0.8032524 0.5367175 -0.2583019 -0.8664366 0.4272797 0.258302 -0.6348644 0.3130807 0.7063481 -0.2325924 0.1147017 0.9657869 0.2325924 -0.1147017 0.965787 0.6348642 -0.3130796 0.7063488 0.8664369 -0.427279 0.258302 0.8664369 -0.427279 -0.258302 0.6348642 -0.3130795 -0.7063488 0.2325925 -0.1147017 -0.9657869 -0.2325923 0.1147017 -0.965787 -0.6348645 0.3130807 -0.7063481 -0.8664366 0.4272796 -0.2583018 -0.9147952 0.3105322 0.2583013 -0.6702975 0.2275365 0.7063487 -0.2455738 0.08336114 0.9657869 0.2455741 -0.0833612 0.9657869 0.6702976 -0.2275357 0.7063489 0.9147952 -0.3105318 0.2583019 0.9147952 -0.3105318 -0.2583019 0.6702975 -0.2275357 -0.7063489 0.2455742 -0.0833612 -0.9657869 -0.2455742 0.08336156 -0.9657869 -0.6702975 0.2275365 -0.7063486 -0.9147955 0.3105312 -0.2583015 -0.9475018 0.1884698 0.2583014 -0.6942628 0.138096 0.7063489 -0.2543538 0.05059409 0.9657869 0.2543543 -0.05059403 0.9657869 0.6942628 -0.1380978 0.7063486 0.9475017 -0.1884692 0.258302 0.9475017 -0.1884692 -0.258302 0.6942628 -0.1380978 -0.7063485 0.2543542 -0.05059403 -0.9657869 -0.2543539 0.05059409 -0.9657869 -0.6942628 0.138096 -0.7063489 -0.9475017 0.1884698 -0.2583014 -0.9639959 0.0631842 0.2583018 -0.7063485 0.04629683 0.7063487 -0.258782 0.01696121 0.9657869 0.2587819 -0.01696157 0.9657869 0.7063486 -0.04629677 0.7063485 0.9639958 -0.06318444 0.2583018 0.9639959 -0.0631836 -0.2583018 0.7063486 -0.04629677 -0.7063486 0.2587816 -0.01696181 -0.965787 -0.2587819 0.01696121 -0.9657869 -0.7063485 0.04629683 -0.7063487 -0.9639959 0.0631842 -0.2583018 -0.9639959 -0.0631839 0.2583016 -0.7063485 -0.04629784 0.7063486 -0.2587817 -0.01696181 0.9657869 0.2587821 0.01696127 0.9657869 0.7063484 0.04629629 0.7063488 0.9639958 0.06318432 0.258302 0.9639959 0.06318354 -0.258302 0.7063484 0.04629629 -0.7063488 0.2587822 0.01696127 -0.9657869 -0.2587817 -0.01696181 -0.9657869 -0.7063485 -0.04629784 -0.7063486 -0.9639959 -0.0631839 -0.2583016 -0.947502 -0.1884685 0.2583016 -0.6942624 -0.1380975 0.706349 -0.2543543 -0.05059379 0.9657868 0.2543539 0.05059409 0.9657869 0.6942627 0.1380969 0.7063487 0.9475018 0.1884691 0.258302 0.9475018 0.1884691 -0.2583019 0.6942628 0.1380969 -0.7063487 0.2543539 0.05059409 -0.9657869 -0.2543544 -0.05059379 -0.9657868 -0.6942624 -0.1380975 -0.706349 -0.947502 -0.1884685 -0.2583016 -0.9147956 -0.3105306 0.2583021 -0.670298 -0.2275354 0.7063485 -0.2455741 -0.08336061 0.965787 0.2455742 0.08336132 0.9657869 0.6702978 0.2275356 0.7063487 0.9147954 0.3105313 0.2583016 0.9147954 0.3105313 -0.2583016 0.6702978 0.2275356 -0.7063488 0.2455742 0.08336132 -0.9657869 -0.2455743 -0.08336061 -0.9657869 -0.670298 -0.2275354 -0.7063485 -0.9147955 -0.3105309 -0.258302 -0.8664363 -0.4272803 0.2583018 -0.6348641 -0.3130797 0.706349 -0.2325922 -0.114702 0.965787 0.2325924 0.1147016 0.9657869 0.6348639 0.3130806 0.7063487 0.8664369 0.4272791 0.2583017 0.8664369 0.4272791 -0.2583017 0.634864 0.3130806 -0.7063487 0.2325921 0.1147018 -0.965787 -0.2325922 -0.114702 -0.9657869 -0.6348642 -0.3130797 -0.7063489 -0.8664363 -0.4272803 -0.2583016 -0.8032527 -0.5367172 0.2583017 -0.5885673 -0.3932686 0.7063487 -0.2156314 -0.1440801 0.9657868 0.2156309 0.14408 0.9657869 0.5885676 0.3932675 0.706349 0.8032533 0.5367164 0.2583019 0.8032533 0.5367164 -0.2583019 0.5885676 0.3932675 -0.706349 0.2156305 0.1440801 -0.9657869 -0.2156314 -0.1440801 -0.9657868 -0.5885673 -0.3932686 -0.7063487 -0.8032528 -0.5367172 -0.2583019 -0.7263259 -0.63697 0.2583021 -0.5322001 -0.4667264 0.7063495 -0.1949803 -0.1709927 0.9657868 0.19498 0.170993 0.9657869 0.5322001 0.4667273 0.7063488 0.7263252 0.6369708 0.2583019 0.7263253 0.6369709 -0.2583016 0.5322001 0.4667273 -0.7063488 0.19498 0.170993 -0.9657869 -0.1949803 -0.1709927 -0.9657868 -0.5322001 -0.4667264 -0.7063495 -0.726326 -0.6369701 -0.2583018 -0.6369707 -0.7263255 0.2583014 -0.4667273 -0.5322 0.706349 -0.1709926 -0.1949794 0.965787 0.1709928 0.1949796 0.965787 0.4667277 0.5322005 0.7063484 0.6369713 0.7263249 0.2583017 0.6369712 0.726325 -0.2583016 0.4667277 0.5322005 -0.7063484 0.1709928 0.1949796 -0.965787 -0.1709927 -0.1949794 -0.965787 -0.4667274 -0.5322001 -0.7063488 -0.6369705 -0.7263254 -0.2583022 -0.5367169 -0.8032528 0.2583022 -0.3932677 -0.588567 0.7063493 -0.1440803 -0.2156312 0.9657868 0.1440796 0.2156304 0.9657871 0.3932681 0.5885673 0.706349 0.5367168 0.8032528 0.2583023 0.5367168 0.8032528 -0.2583021 0.3932681 0.5885672 -0.706349 0.1440796 0.2156304 -0.9657871 -0.1440802 -0.2156311 -0.9657868 -0.3932682 -0.5885667 -0.7063494 -0.5367169 -0.8032526 -0.2583025 -0.4272787 -0.8664366 0.2583033 -0.3130804 -0.634864 0.7063486 -0.1147018 -0.2325921 0.9657869 0.1147016 0.2325924 0.9657869 0.3130804 0.6348643 0.7063484 0.4272791 0.8664368 0.2583017 0.4272791 0.8664368 -0.2583018 0.3130803 0.6348641 -0.7063487 0.1147016 0.2325924 -0.9657869 -0.1147019 -0.2325922 -0.965787 -0.3130803 -0.6348645 -0.7063483 -0.4272788 -0.8664362 -0.2583044 -0.3105316 -0.9147953 0.2583017 -0.2275354 -0.670298 0.7063485 -0.08336132 -0.2455744 0.9657868 0.08336114 0.2455738 0.965787 0.2275359 0.6702978 0.7063487 0.3105317 0.9147951 0.2583025 0.3105311 0.9147951 -0.2583029 0.2275358 0.6702979 -0.7063486 0.08336114 0.2455738 -0.965787 -0.08336132 -0.2455744 -0.9657868 -0.2275354 -0.6702978 -0.7063488 -0.3105316 -0.9147953 -0.2583017 -0.1884698 -0.9475016 0.2583018 -0.1380978 -0.6942628 0.7063485 -0.05059427 -0.2543537 0.965787 0.05059415 0.2543538 0.9657869 0.1380976 0.6942625 0.7063489 0.1884697 0.9475015 0.2583026 0.1884697 0.9475015 -0.2583025 0.1380977 0.6942626 -0.7063487 0.05059427 0.2543539 -0.9657869 -0.05059438 -0.2543538 -0.965787 -0.138098 -0.6942629 -0.7063484 -0.1884698 -0.9475016 -0.2583017 -0.06318366 -0.9639956 0.2583031 -0.04629653 -0.7063496 0.7063476 -0.01696151 -0.2587816 0.965787 0.01696151 0.2587818 0.9657869 0.04629689 0.7063491 0.7063481 0.06318384 0.9639956 0.2583031 0.06318384 0.9639955 -0.2583034 0.04629677 0.7063491 -0.7063481 0.01696151 0.2587818 -0.9657869 -0.01696139 -0.2587819 -0.9657869 -0.04629647 -0.7063493 -0.706348 -0.0631839 -0.963996 -0.2583013 0.06318342 -0.9639962 0.2583007 0.04629635 -0.7063487 0.7063486 0.01696121 -0.2587815 0.965787 -0.01696157 0.2587817 0.9657869 -0.04629671 0.7063483 0.7063488 -0.06318342 0.963996 0.2583015 -0.06318378 0.9639962 -0.2583009 -0.04629671 0.7063484 -0.7063487 -0.01696157 0.2587817 -0.9657869 0.01696127 -0.2587813 -0.9657871 0.04629635 -0.706348 -0.7063491 0.06318366 -0.9639963 -0.2583004 0.1884698 -0.9475016 0.2583021 0.1380971 -0.694262 0.7063494 0.05059403 -0.2543538 0.965787 -0.05059409 0.2543537 0.965787 -0.1380973 0.6942631 0.7063483 -0.1884697 0.9475015 0.2583026 -0.1884692 0.9475018 -0.258302 -0.1380974 0.6942632 -0.7063482 -0.05059397 0.2543537 -0.965787 0.05059403 -0.2543537 -0.965787 0.1380971 -0.694262 -0.7063494 0.1884691 -0.9475015 -0.2583031 0.3105312 -0.9147955 0.2583017 0.2275357 -0.6702982 0.7063482 0.08336108 -0.2455741 0.9657869 -0.08336108 0.245574 0.965787 -0.2275356 0.670298 0.7063485 -0.3105312 0.9147957 0.258301 -0.3105311 0.9147956 -0.2583011 -0.2275351 0.670298 -0.7063486 -0.08336108 0.245574 -0.965787 0.08336156 -0.2455745 -0.9657867 0.2275356 -0.6702983 -0.7063483 0.3105311 -0.9147953 -0.2583023 0.4272794 -0.8664366 0.2583023 0.3130804 -0.634864 0.7063487 0.1147015 -0.2325921 0.9657871 -0.114702 0.2325924 0.9657869 -0.3130802 0.6348643 0.7063485 -0.4272792 0.8664371 0.258301 -0.4272791 0.866437 -0.258301 -0.3130801 0.634864 -0.7063487 -0.114702 0.2325924 -0.9657869 0.1147015 -0.232592 -0.965787 0.3130804 -0.634864 -0.7063487 0.4272795 -0.866437 -0.2583006 0.5367162 -0.8032531 0.2583023 0.3932681 -0.5885674 0.7063488 0.1440798 -0.2156308 0.9657869 -0.1440802 0.215631 0.9657868 -0.3932687 0.5885669 0.7063489 -0.5367169 0.8032532 0.2583009 -0.5367169 0.8032532 -0.2583009 -0.3932687 0.5885669 -0.7063489 -0.1440801 0.215631 -0.9657869 0.1440798 -0.2156308 -0.9657869 0.393268 -0.5885673 -0.706349 0.5367162 -0.8032531 -0.2583029 0.6369703 -0.726326 0.2583012 0.4667266 -0.5322007 0.7063488 0.1709928 -0.1949802 0.9657869 -0.1709927 0.1949802 0.9657869 -0.4667271 0.5322003 0.7063488 -0.63697 0.7263261 0.2583017 -0.6369701 0.7263261 -0.2583015 -0.4667271 0.5322003 -0.7063488 -0.1709927 0.1949802 -0.9657869 0.1709928 -0.1949802 -0.9657869 0.4667268 -0.5322008 -0.7063487 0.6369703 -0.726326 -0.258301 0.7263252 -0.6369706 0.2583024 0.5322001 -0.4667276 0.7063486 0.1949797 -0.170993 0.9657869 -0.19498 0.1709926 0.9657869 -0.5322002 0.4667273 0.7063488 -0.7263254 0.6369706 0.2583021 -0.7263253 0.6369706 -0.2583023 -0.5322002 0.4667273 -0.7063488 -0.1949799 0.1709927 -0.9657869 0.1949797 -0.170993 -0.9657869 0.5322001 -0.4667276 -0.7063486 0.7263252 -0.6369706 -0.2583025 0.8032531 -0.5367164 0.258302 0.5885675 -0.3932685 0.7063485 0.2156308 -0.14408 0.9657869 -0.2156307 0.1440798 0.9657869 -0.5885678 0.3932676 0.7063488 -0.8032532 0.5367163 0.258302 -0.8032532 0.5367163 -0.258302 -0.5885677 0.3932676 -0.7063489 -0.2156307 0.1440798 -0.9657869 0.215631 -0.14408 -0.9657869 0.5885674 -0.3932685 -0.7063486 0.8032531 -0.5367164 -0.258302 0.8664364 -0.4272798 0.258302 0.6348641 -0.3130802 0.7063487 0.2325925 -0.1147021 0.9657869 -0.2325922 0.1147019 0.9657869 -0.634864 0.3130806 0.7063485 -0.8664366 0.4272795 0.258302 -0.8664366 0.4272795 -0.258302 -0.6348644 0.3130799 -0.7063485 -0.2325922 0.1147019 -0.9657869 0.2325925 -0.1147021 -0.9657869 0.634864 -0.3130801 -0.7063488 0.8664364 -0.4272798 -0.258302 0.9147955 -0.3105311 0.2583017 0.6702977 -0.2275352 0.7063489 0.2455742 -0.08336132 0.9657869 -0.2455739 0.08336091 0.9657869 -0.6702979 0.227535 0.7063488 -0.9147953 0.3105314 0.2583017 -0.9147953 0.3105314 -0.2583018 -0.6702978 0.227535 -0.7063488 -0.2455742 0.08336114 -0.9657869 0.2455743 -0.08336138 -0.9657869 0.6702978 -0.2275357 -0.7063487 0.9147955 -0.3105311 -0.2583016 0.9475018 -0.1884698 0.2583016 0.6942629 -0.1380976 0.7063485 0.254354 -0.0505945 0.9657869 -0.2543538 0.0505945 0.9657869 -0.6942627 0.1380969 0.7063488 -0.9475018 0.1884692 0.2583016 -0.9475018 0.1884692 -0.2583016 -0.6942628 0.1380969 -0.7063488 -0.2543538 0.0505945 -0.9657869 0.2543541 -0.0505945 -0.9657869 0.6942628 -0.1380976 -0.7063485 0.947502 -0.1884685 -0.2583016 0.9639959 -0.06318402 0.2583018 0.7063484 -0.04629641 0.7063488 0.2587817 -0.01696139 0.965787 -0.258782 0.01696157 0.9657869 -0.7063485 0.04629641 0.7063487 -0.9639959 0.0631833 0.2583019 -0.9639959 0.0631833 -0.2583019 -0.7063485 0.04629641 -0.7063487 -0.258782 0.01696157 -0.9657869 0.2587817 -0.01696139 -0.965787 0.7063484 -0.04629641 -0.7063488 0.9639959 -0.06318402 -0.2583018 + + + + + + + + + + 0.5 0.5 0.5208333 0.5833333 0.5 0.5833333 0.5 0.5833333 0.5208333 0.6666667 0.5 0.6666667 0.5 0.6666667 0.5208333 0.75 0.5 0.75 0.5 0.75 0.5208333 0.8333333 0.5 0.8333333 0.5208333 0.8333333 0.5 0.9166667 0.5 0.8333333 0.5 0.9166667 0.5208333 1 0.5 1 0.5208333 0 0.5 0.08333331 0.5 0 0.5 0.08333331 0.5208333 0.1666666 0.5 0.1666666 0.5208333 0.1666666 0.5 0.25 0.5 0.1666666 0.5208333 0.25 0.5 0.3333333 0.5 0.25 0.5208333 0.3333333 0.5 0.4166666 0.5 0.3333333 0.5208333 0.4166666 0.5 0.5 0.5 0.4166666 0.5416667 0.5 0.5208333 0.5833333 0.5208333 0.5 0.5416667 0.5833333 0.5208333 0.6666667 0.5208333 0.5833333 0.5416667 0.6666667 0.5208333 0.75 0.5208333 0.6666667 0.5416667 0.75 0.5208333 0.8333333 0.5208333 0.75 0.5416667 0.8333333 0.5208333 0.9166667 0.5208333 0.8333333 0.5208333 0.9166667 0.5416667 1 0.5208333 1 0.5416667 0 0.5208333 0.08333331 0.5208333 0 0.5208333 0.08333331 0.5416667 0.1666666 0.5208333 0.1666666 0.5208333 0.1666666 0.5416667 0.25 0.5208333 0.25 0.5208333 0.25 0.5416667 0.3333333 0.5208333 0.3333333 0.5208333 0.3333333 0.5416667 0.4166666 0.5208333 0.4166666 0.5208333 0.4166666 0.5416667 0.5 0.5208333 0.5 0.5416667 0.5 0.5625 0.5833333 0.5416667 0.5833333 0.5625 0.5833333 0.5416667 0.6666667 0.5416667 0.5833333 0.5625 0.6666667 0.5416667 0.75 0.5416667 0.6666667 0.5416667 0.75 0.5625 0.8333333 0.5416667 0.8333333 0.5416667 0.8333333 0.5625 0.9166667 0.5416667 0.9166667 0.5416667 0.9166667 0.5625 1 0.5416667 1 0.5625 0 0.5416667 0.08333331 0.5416667 0 0.5625 0.08333331 0.5416667 0.1666666 0.5416667 0.08333331 0.5625 0.1666666 0.5416667 0.25 0.5416667 0.1666666 0.5416667 0.25 0.5625 0.3333333 0.5416667 0.3333333 0.5625 0.3333333 0.5416667 0.4166666 0.5416667 0.3333333 0.5625 0.4166666 0.5416667 0.5 0.5416667 0.4166666 0.5625 0.5 0.5833333 0.5833333 0.5625 0.5833333 0.5833333 0.5833333 0.5625 0.6666667 0.5625 0.5833333 0.5625 0.6666667 0.5833333 0.75 0.5625 0.75 0.5833333 0.75 0.5625 0.8333333 0.5625 0.75 0.5833333 0.8333333 0.5625 0.9166667 0.5625 0.8333333 0.5833333 0.9166667 0.5625 1 0.5625 0.9166667 0.5625 0 0.5833333 0.08333331 0.5625 0.08333331 0.5833333 0.08333331 0.5625 0.1666666 0.5625 0.08333331 0.5625 0.1666666 0.5833333 0.25 0.5625 0.25 0.5833333 0.25 0.5625 0.3333333 0.5625 0.25 0.5625 0.3333333 0.5833333 0.4166666 0.5625 0.4166666 0.5833333 0.4166666 0.5625 0.5 0.5625 0.4166666 0.6041667 0.5 0.5833333 0.5833333 0.5833333 0.5 0.5833333 0.5833333 0.6041667 0.6666667 0.5833333 0.6666667 0.6041667 0.6666667 0.5833333 0.75 0.5833333 0.6666667 0.6041667 0.75 0.5833333 0.8333333 0.5833333 0.75 0.5833333 0.8333333 0.6041667 0.9166667 0.5833333 0.9166667 0.6041667 0.9166667 0.5833333 1 0.5833333 0.9166667 0.5833333 0 0.6041667 0.08333331 0.5833333 0.08333331 0.6041667 0.08333331 0.5833333 0.1666666 0.5833333 0.08333331 0.5833333 0.1666666 0.6041667 0.25 0.5833333 0.25 0.6041667 0.25 0.5833333 0.3333333 0.5833333 0.25 0.6041667 0.3333333 0.5833333 0.4166666 0.5833333 0.3333333 0.5833333 0.4166666 0.6041667 0.5 0.5833333 0.5 0.625 0.5 0.6041667 0.5833333 0.6041667 0.5 0.625 0.5833333 0.6041667 0.6666667 0.6041667 0.5833333 0.625 0.6666667 0.6041667 0.75 0.6041667 0.6666667 0.625 0.75 0.6041667 0.8333333 0.6041667 0.75 0.6041667 0.8333333 0.625 0.9166667 0.6041667 0.9166667 0.625 0.9166667 0.6041667 1 0.6041667 0.9166667 0.625 0 0.6041667 0.08333331 0.6041667 0 0.625 0.08333331 0.6041667 0.1666666 0.6041667 0.08333331 0.6041667 0.1666666 0.625 0.25 0.6041667 0.25 0.6041667 0.25 0.625 0.3333333 0.6041667 0.3333333 0.6041667 0.3333333 0.625 0.4166666 0.6041667 0.4166666 0.6041667 0.4166666 0.625 0.5 0.6041667 0.5 0.625 0.5 0.6458333 0.5833333 0.625 0.5833333 0.625 0.5833333 0.6458333 0.6666667 0.625 0.6666667 0.6458333 0.6666667 0.625 0.75 0.625 0.6666667 0.6458333 0.75 0.625 0.8333333 0.625 0.75 0.6458333 0.8333333 0.625 0.9166667 0.625 0.8333333 0.6458333 0.9166667 0.625 1 0.625 0.9166667 0.625 0 0.6458333 0.08333331 0.625 0.08333331 0.625 0.08333331 0.6458333 0.1666666 0.625 0.1666666 0.625 0.1666666 0.6458333 0.25 0.625 0.25 0.625 0.25 0.6458333 0.3333333 0.625 0.3333333 0.6458333 0.3333333 0.625 0.4166666 0.625 0.3333333 0.6458333 0.4166666 0.625 0.5 0.625 0.4166666 0.6458333 0.5 0.6666667 0.5833333 0.6458333 0.5833333 0.6458333 0.5833333 0.6666667 0.6666667 0.6458333 0.6666667 0.6458333 0.6666667 0.6666667 0.75 0.6458333 0.75 0.6458333 0.75 0.6666667 0.8333333 0.6458333 0.8333333 0.6458333 0.8333333 0.6666667 0.9166667 0.6458333 0.9166667 0.6458333 0.9166667 0.6666667 1 0.6458333 1 0.6666667 0 0.6458333 0.08333331 0.6458333 0 0.6666667 0.08333331 0.6458333 0.1666666 0.6458333 0.08333331 0.6666667 0.1666666 0.6458333 0.25 0.6458333 0.1666666 0.6666667 0.25 0.6458333 0.3333333 0.6458333 0.25 0.6666667 0.3333333 0.6458333 0.4166666 0.6458333 0.3333333 0.6666667 0.4166666 0.6458333 0.5 0.6458333 0.4166666 0.6875 0.5 0.6666667 0.5833333 0.6666667 0.5 0.6875 0.5833333 0.6666667 0.6666667 0.6666667 0.5833333 0.6875 0.6666667 0.6666667 0.75 0.6666667 0.6666667 0.6875 0.75 0.6666667 0.8333333 0.6666667 0.75 0.6875 0.8333333 0.6666667 0.9166667 0.6666667 0.8333333 0.6875 0.9166667 0.6666667 1 0.6666667 0.9166667 0.6666667 0 0.6875 0.08333331 0.6666667 0.08333331 0.6666667 0.08333331 0.6875 0.1666666 0.6666667 0.1666666 0.6666667 0.1666666 0.6875 0.25 0.6666667 0.25 0.6666667 0.25 0.6875 0.3333333 0.6666667 0.3333333 0.6666667 0.3333333 0.6875 0.4166666 0.6666667 0.4166666 0.6875 0.4166666 0.6666667 0.5 0.6666667 0.4166666 0.7083333 0.5 0.6875 0.5833333 0.6875 0.5 0.6875 0.5833333 0.7083333 0.6666667 0.6875 0.6666667 0.6875 0.6666667 0.7083333 0.75 0.6875 0.75 0.7083333 0.75 0.6875 0.8333333 0.6875 0.75 0.6875 0.8333333 0.7083333 0.9166667 0.6875 0.9166667 0.7083333 0.9166667 0.6875 1 0.6875 0.9166667 0.6875 0 0.7083333 0.08333331 0.6875 0.08333331 0.7083333 0.08333331 0.6875 0.1666666 0.6875 0.08333331 0.7083333 0.1666666 0.6875 0.25 0.6875 0.1666666 0.7083333 0.25 0.6875 0.3333333 0.6875 0.25 0.7083333 0.3333333 0.6875 0.4166666 0.6875 0.3333333 0.6875 0.4166666 0.7083333 0.5 0.6875 0.5 0.7291667 0.5 0.7083333 0.5833333 0.7083333 0.5 0.7083333 0.5833333 0.7291667 0.6666667 0.7083333 0.6666667 0.7291667 0.6666667 0.7083333 0.75 0.7083333 0.6666667 0.7291667 0.75 0.7083333 0.8333333 0.7083333 0.75 0.7291667 0.8333333 0.7083333 0.9166667 0.7083333 0.8333333 0.7291667 0.9166667 0.7083333 1 0.7083333 0.9166667 0.7083333 0 0.7291667 0.08333331 0.7083333 0.08333331 0.7083333 0.08333331 0.7291667 0.1666666 0.7083333 0.1666666 0.7083333 0.1666666 0.7291667 0.25 0.7083333 0.25 0.7291667 0.25 0.7083333 0.3333333 0.7083333 0.25 0.7291667 0.3333333 0.7083333 0.4166666 0.7083333 0.3333333 0.7083333 0.4166666 0.7291667 0.5 0.7083333 0.5 0.75 0.5 0.7291667 0.5833333 0.7291667 0.5 0.75 0.5833333 0.7291667 0.6666667 0.7291667 0.5833333 0.75 0.6666667 0.7291667 0.75 0.7291667 0.6666667 0.7291667 0.75 0.75 0.8333333 0.7291667 0.8333333 0.7291667 0.8333333 0.75 0.9166667 0.7291667 0.9166667 0.75 0.9166667 0.7291667 1 0.7291667 0.9166667 0.75 0 0.7291667 0.08333331 0.7291667 0 0.75 0.08333331 0.7291667 0.1666666 0.7291667 0.08333331 0.75 0.1666666 0.7291667 0.25 0.7291667 0.1666666 0.7291667 0.25 0.75 0.3333333 0.7291667 0.3333333 0.75 0.3333333 0.7291667 0.4166666 0.7291667 0.3333333 0.75 0.4166666 0.7291667 0.5 0.7291667 0.4166666 0.7708333 0.5 0.75 0.5833333 0.75 0.5 0.7708333 0.5833333 0.75 0.6666667 0.75 0.5833333 0.7708333 0.6666667 0.75 0.75 0.75 0.6666667 0.7708333 0.75 0.75 0.8333333 0.75 0.75 0.75 0.8333333 0.7708333 0.9166667 0.75 0.9166667 0.7708333 0.9166667 0.75 1 0.75 0.9166667 0.7708333 0 0.75 0.08333331 0.75 0 0.7708333 0.08333331 0.75 0.1666666 0.75 0.08333331 0.75 0.1666666 0.7708333 0.25 0.75 0.25 0.75 0.25 0.7708333 0.3333333 0.75 0.3333333 0.75 0.3333333 0.7708333 0.4166666 0.75 0.4166666 0.75 0.4166666 0.7708333 0.5 0.75 0.5 0.7708333 0.5 0.7916667 0.5833333 0.7708333 0.5833333 0.7708333 0.5833333 0.7916667 0.6666667 0.7708333 0.6666667 0.7708333 0.6666667 0.7916667 0.75 0.7708333 0.75 0.7708333 0.75 0.7916667 0.8333333 0.7708333 0.8333333 0.7708333 0.8333333 0.7916667 0.9166667 0.7708333 0.9166667 0.7916667 0.9166667 0.7708333 1 0.7708333 0.9166667 0.7708333 0 0.7916667 0.08333331 0.7708333 0.08333331 0.7916667 0.08333331 0.7708333 0.1666666 0.7708333 0.08333331 0.7916667 0.1666666 0.7708333 0.25 0.7708333 0.1666666 0.7916667 0.25 0.7708333 0.3333333 0.7708333 0.25 0.7916667 0.3333333 0.7708333 0.4166666 0.7708333 0.3333333 0.7916667 0.4166666 0.7708333 0.5 0.7708333 0.4166666 0.8125 0.5 0.7916667 0.5833333 0.7916667 0.5 0.8125 0.5833333 0.7916667 0.6666667 0.7916667 0.5833333 0.7916667 0.6666667 0.8125 0.75 0.7916667 0.75 0.8125 0.75 0.7916667 0.8333333 0.7916667 0.75 0.8125 0.8333333 0.7916667 0.9166667 0.7916667 0.8333333 0.8125 0.9166667 0.7916667 1 0.7916667 0.9166667 0.7916667 0 0.8125 0.08333331 0.7916667 0.08333331 0.7916667 0.08333331 0.8125 0.1666666 0.7916667 0.1666666 0.7916667 0.1666666 0.8125 0.25 0.7916667 0.25 0.8125 0.25 0.7916667 0.3333333 0.7916667 0.25 0.7916667 0.3333333 0.8125 0.4166666 0.7916667 0.4166666 0.8125 0.4166666 0.7916667 0.5 0.7916667 0.4166666 0.8333333 0.5 0.8125 0.5833333 0.8125 0.5 0.8333333 0.5833333 0.8125 0.6666667 0.8125 0.5833333 0.8333333 0.6666667 0.8125 0.75 0.8125 0.6666667 0.8125 0.75 0.8333333 0.8333333 0.8125 0.8333333 0.8125 0.8333333 0.8333333 0.9166667 0.8125 0.9166667 0.8125 0.9166667 0.8333333 1 0.8125 1 0.8333333 0 0.8125 0.08333331 0.8125 0 0.8333333 0.08333331 0.8125 0.1666666 0.8125 0.08333331 0.8333333 0.1666666 0.8125 0.25 0.8125 0.1666666 0.8125 0.25 0.8333333 0.3333333 0.8125 0.3333333 0.8333333 0.3333333 0.8125 0.4166666 0.8125 0.3333333 0.8333333 0.4166666 0.8125 0.5 0.8125 0.4166666 0.8541667 0.5 0.8333333 0.5833333 0.8333333 0.5 0.8541667 0.5833333 0.8333333 0.6666667 0.8333333 0.5833333 0.8541667 0.6666667 0.8333333 0.75 0.8333333 0.6666667 0.8541667 0.75 0.8333333 0.8333333 0.8333333 0.75 0.8541667 0.8333333 0.8333333 0.9166667 0.8333333 0.8333333 0.8333333 0.9166667 0.8541667 1 0.8333333 1 0.8541667 0 0.8333333 0.08333331 0.8333333 0 0.8333333 0.08333331 0.8541667 0.1666666 0.8333333 0.1666666 0.8333333 0.1666666 0.8541667 0.25 0.8333333 0.25 0.8333333 0.25 0.8541667 0.3333333 0.8333333 0.3333333 0.8333333 0.3333333 0.8541667 0.4166666 0.8333333 0.4166666 0.8333333 0.4166666 0.8541667 0.5 0.8333333 0.5 0.8541667 0.5 0.875 0.5833333 0.8541667 0.5833333 0.875 0.5833333 0.8541667 0.6666667 0.8541667 0.5833333 0.8541667 0.6666667 0.875 0.75 0.8541667 0.75 0.875 0.75 0.8541667 0.8333333 0.8541667 0.75 0.875 0.8333333 0.8541667 0.9166667 0.8541667 0.8333333 0.8541667 0.9166667 0.875 1 0.8541667 1 0.875 0 0.8541667 0.08333331 0.8541667 0 0.8541667 0.08333331 0.875 0.1666666 0.8541667 0.1666666 0.8541667 0.1666666 0.875 0.25 0.8541667 0.25 0.875 0.25 0.8541667 0.3333333 0.8541667 0.25 0.875 0.3333333 0.8541667 0.4166666 0.8541667 0.3333333 0.875 0.4166666 0.8541667 0.5 0.8541667 0.4166666 0.875 0.5 0.8958333 0.5833333 0.875 0.5833333 0.8958333 0.5833333 0.875 0.6666667 0.875 0.5833333 0.8958333 0.6666667 0.875 0.75 0.875 0.6666667 0.875 0.75 0.8958333 0.8333333 0.875 0.8333333 0.875 0.8333333 0.8958333 0.9166667 0.875 0.9166667 0.875 0.9166667 0.8958333 1 0.875 1 0.8958333 0 0.875 0.08333331 0.875 0 0.8958333 0.08333331 0.875 0.1666666 0.875 0.08333331 0.8958333 0.1666666 0.875 0.25 0.875 0.1666666 0.875 0.25 0.8958333 0.3333333 0.875 0.3333333 0.875 0.3333333 0.8958333 0.4166666 0.875 0.4166666 0.8958333 0.4166666 0.875 0.5 0.875 0.4166666 0.8958333 0.5 0.9166667 0.5833333 0.8958333 0.5833333 0.9166667 0.5833333 0.8958333 0.6666667 0.8958333 0.5833333 0.8958333 0.6666667 0.9166667 0.75 0.8958333 0.75 0.9166667 0.75 0.8958333 0.8333333 0.8958333 0.75 0.9166667 0.8333333 0.8958333 0.9166667 0.8958333 0.8333333 0.9166667 0.9166667 0.8958333 1 0.8958333 0.9166667 0.8958333 0 0.9166667 0.08333331 0.8958333 0.08333331 0.8958333 0.08333331 0.9166667 0.1666666 0.8958333 0.1666666 0.9166667 0.1666666 0.8958333 0.25 0.8958333 0.1666666 0.9166667 0.25 0.8958333 0.3333333 0.8958333 0.25 0.8958333 0.3333333 0.9166667 0.4166666 0.8958333 0.4166666 0.9166667 0.4166666 0.8958333 0.5 0.8958333 0.4166666 0.9166667 0.5 0.9375 0.5833333 0.9166667 0.5833333 0.9375 0.5833333 0.9166667 0.6666667 0.9166667 0.5833333 0.9166667 0.6666667 0.9375 0.75 0.9166667 0.75 0.9166667 0.75 0.9375 0.8333333 0.9166667 0.8333333 0.9375 0.8333333 0.9166667 0.9166667 0.9166667 0.8333333 0.9375 0.9166667 0.9166667 1 0.9166667 0.9166667 0.9166667 0 0.9375 0.08333331 0.9166667 0.08333331 0.9375 0.08333331 0.9166667 0.1666666 0.9166667 0.08333331 0.9375 0.1666666 0.9166667 0.25 0.9166667 0.1666666 0.9375 0.25 0.9166667 0.3333333 0.9166667 0.25 0.9166667 0.3333333 0.9375 0.4166666 0.9166667 0.4166666 0.9375 0.4166666 0.9166667 0.5 0.9166667 0.4166666 0.9583333 0.5 0.9375 0.5833333 0.9375 0.5 0.9375 0.5833333 0.9583333 0.6666667 0.9375 0.6666667 0.9583333 0.6666667 0.9375 0.75 0.9375 0.6666667 0.9375 0.75 0.9583333 0.8333333 0.9375 0.8333333 0.9375 0.8333333 0.9583333 0.9166667 0.9375 0.9166667 0.9375 0.9166667 0.9583333 1 0.9375 1 0.9583333 0 0.9375 0.08333331 0.9375 0 0.9583333 0.08333331 0.9375 0.1666666 0.9375 0.08333331 0.9583333 0.1666666 0.9375 0.25 0.9375 0.1666666 0.9583333 0.25 0.9375 0.3333333 0.9375 0.25 0.9583333 0.3333333 0.9375 0.4166666 0.9375 0.3333333 0.9583333 0.4166666 0.9375 0.5 0.9375 0.4166666 0.9791667 0.5 0.9583333 0.5833333 0.9583333 0.5 0.9791667 0.5833333 0.9583333 0.6666667 0.9583333 0.5833333 0.9791667 0.6666667 0.9583333 0.75 0.9583333 0.6666667 0.9791667 0.75 0.9583333 0.8333333 0.9583333 0.75 0.9791667 0.8333333 0.9583333 0.9166667 0.9583333 0.8333333 0.9583333 0.9166667 0.9791667 1 0.9583333 1 0.9791667 0 0.9583333 0.08333331 0.9583333 0 0.9583333 0.08333331 0.9791667 0.1666666 0.9583333 0.1666666 0.9583333 0.1666666 0.9791667 0.25 0.9583333 0.25 0.9583333 0.25 0.9791667 0.3333333 0.9583333 0.3333333 0.9583333 0.3333333 0.9791667 0.4166666 0.9583333 0.4166666 0.9583333 0.4166666 0.9791667 0.5 0.9583333 0.5 0.9791667 0.5 1 0.5833333 0.9791667 0.5833333 0.9791667 0.5833333 1 0.6666667 0.9791667 0.6666667 0.9791667 0.6666667 1 0.75 0.9791667 0.75 1 0.75 0.9791667 0.8333333 0.9791667 0.75 1 0.8333333 0.9791667 0.9166667 0.9791667 0.8333333 1 0.9166667 0.9791667 1 0.9791667 0.9166667 1 0 0.9791667 0.08333331 0.9791667 0 0.9791667 0.08333331 1 0.1666666 0.9791667 0.1666666 1 0.1666666 0.9791667 0.25 0.9791667 0.1666666 1 0.25 0.9791667 0.3333333 0.9791667 0.25 1 0.3333333 0.9791667 0.4166666 0.9791667 0.3333333 1 0.4166666 0.9791667 0.5 0.9791667 0.4166666 0.02083331 0.5 0 0.5833333 0 0.5 0.02083331 0.5833333 0 0.6666667 0 0.5833333 0.02083331 0.6666667 0 0.75 0 0.6666667 0.02083331 0.75 0 0.8333333 0 0.75 0 0.8333333 0.02083331 0.9166667 0 0.9166667 0.02083331 0.9166667 0 1 0 0.9166667 0.02083331 0 0 0.08333331 0 0 0.02083331 0.08333331 0 0.1666666 0 0.08333331 0 0.1666666 0.02083331 0.25 0 0.25 0 0.25 0.02083331 0.3333333 0 0.3333333 0 0.3333333 0.02083331 0.4166666 0 0.4166666 0 0.4166666 0.02083331 0.5 0 0.5 0.02083331 0.5 0.04166662 0.5833333 0.02083331 0.5833333 0.02083331 0.5833333 0.04166662 0.6666667 0.02083331 0.6666667 0.02083331 0.6666667 0.04166662 0.75 0.02083331 0.75 0.02083331 0.75 0.04166662 0.8333333 0.02083331 0.8333333 0.02083331 0.8333333 0.04166662 0.9166667 0.02083331 0.9166667 0.04166662 0.9166667 0.02083331 1 0.02083331 0.9166667 0.02083331 0 0.04166662 0.08333331 0.02083331 0.08333331 0.04166662 0.08333331 0.02083331 0.1666666 0.02083331 0.08333331 0.04166662 0.1666666 0.02083331 0.25 0.02083331 0.1666666 0.04166662 0.25 0.02083331 0.3333333 0.02083331 0.25 0.04166662 0.3333333 0.02083331 0.4166666 0.02083331 0.3333333 0.04166662 0.4166666 0.02083331 0.5 0.02083331 0.4166666 0.0625 0.5 0.04166662 0.5833333 0.04166662 0.5 0.0625 0.5833333 0.04166662 0.6666667 0.04166662 0.5833333 0.04166662 0.6666667 0.0625 0.75 0.04166662 0.75 0.0625 0.75 0.04166662 0.8333333 0.04166662 0.75 0.0625 0.8333333 0.04166662 0.9166667 0.04166662 0.8333333 0.0625 0.9166667 0.04166662 1 0.04166662 0.9166667 0.04166662 0 0.0625 0.08333331 0.04166662 0.08333331 0.04166662 0.08333331 0.0625 0.1666666 0.04166662 0.1666666 0.04166662 0.1666666 0.0625 0.25 0.04166662 0.25 0.0625 0.25 0.04166662 0.3333333 0.04166662 0.25 0.04166662 0.3333333 0.0625 0.4166666 0.04166662 0.4166666 0.0625 0.4166666 0.04166662 0.5 0.04166662 0.4166666 0.08333331 0.5 0.0625 0.5833333 0.0625 0.5 0.08333331 0.5833333 0.0625 0.6666667 0.0625 0.5833333 0.08333331 0.6666667 0.0625 0.75 0.0625 0.6666667 0.08333331 0.75 0.0625 0.8333333 0.0625 0.75 0.08333331 0.8333333 0.0625 0.9166667 0.0625 0.8333333 0.0625 0.9166667 0.08333331 1 0.0625 1 0.08333331 0 0.0625 0.08333331 0.0625 0 0.0625 0.08333331 0.08333331 0.1666666 0.0625 0.1666666 0.08333331 0.1666666 0.0625 0.25 0.0625 0.1666666 0.0625 0.25 0.08333331 0.3333333 0.0625 0.3333333 0.0625 0.3333333 0.08333331 0.4166666 0.0625 0.4166666 0.0625 0.4166666 0.08333331 0.5 0.0625 0.5 0.1041666 0.5 0.08333331 0.5833333 0.08333331 0.5 0.1041666 0.5833333 0.08333331 0.6666667 0.08333331 0.5833333 0.1041666 0.6666667 0.08333331 0.75 0.08333331 0.6666667 0.1041666 0.75 0.08333331 0.8333333 0.08333331 0.75 0.08333331 0.8333333 0.1041666 0.9166667 0.08333331 0.9166667 0.08333331 0.9166667 0.1041666 1 0.08333331 1 0.1041666 0 0.08333331 0.08333331 0.08333331 0 0.1041666 0.08333331 0.08333331 0.1666666 0.08333331 0.08333331 0.1041666 0.1666666 0.08333331 0.25 0.08333331 0.1666666 0.08333331 0.25 0.1041666 0.3333333 0.08333331 0.3333333 0.08333331 0.3333333 0.1041666 0.4166666 0.08333331 0.4166666 0.08333331 0.4166666 0.1041666 0.5 0.08333331 0.5 0.125 0.5 0.1041666 0.5833333 0.1041666 0.5 0.1041666 0.5833333 0.125 0.6666667 0.1041666 0.6666667 0.1041666 0.6666667 0.125 0.75 0.1041666 0.75 0.125 0.75 0.1041666 0.8333333 0.1041666 0.75 0.125 0.8333333 0.1041666 0.9166667 0.1041666 0.8333333 0.125 0.9166667 0.1041666 1 0.1041666 0.9166667 0.1041666 0 0.125 0.08333331 0.1041666 0.08333331 0.1041666 0.08333331 0.125 0.1666666 0.1041666 0.1666666 0.1041666 0.1666666 0.125 0.25 0.1041666 0.25 0.125 0.25 0.1041666 0.3333333 0.1041666 0.25 0.125 0.3333333 0.1041666 0.4166666 0.1041666 0.3333333 0.1041666 0.4166666 0.125 0.5 0.1041666 0.5 0.1458333 0.5 0.125 0.5833333 0.125 0.5 0.125 0.5833333 0.1458333 0.6666667 0.125 0.6666667 0.125 0.6666667 0.1458333 0.75 0.125 0.75 0.125 0.75 0.1458333 0.8333333 0.125 0.8333333 0.125 0.8333333 0.1458333 0.9166667 0.125 0.9166667 0.1458333 0.9166667 0.125 1 0.125 0.9166667 0.1458333 0 0.125 0.08333331 0.125 0 0.1458333 0.08333331 0.125 0.1666666 0.125 0.08333331 0.1458333 0.1666666 0.125 0.25 0.125 0.1666666 0.1458333 0.25 0.125 0.3333333 0.125 0.25 0.1458333 0.3333333 0.125 0.4166666 0.125 0.3333333 0.1458333 0.4166666 0.125 0.5 0.125 0.4166666 0.1458333 0.5 0.1666666 0.5833333 0.1458333 0.5833333 0.1666666 0.5833333 0.1458333 0.6666667 0.1458333 0.5833333 0.1458333 0.6666667 0.1666666 0.75 0.1458333 0.75 0.1458333 0.75 0.1666666 0.8333333 0.1458333 0.8333333 0.1458333 0.8333333 0.1666666 0.9166667 0.1458333 0.9166667 0.1666666 0.9166667 0.1458333 1 0.1458333 0.9166667 0.1458333 0 0.1666666 0.08333331 0.1458333 0.08333331 0.1666666 0.08333331 0.1458333 0.1666666 0.1458333 0.08333331 0.1666666 0.1666666 0.1458333 0.25 0.1458333 0.1666666 0.1666666 0.25 0.1458333 0.3333333 0.1458333 0.25 0.1666666 0.3333333 0.1458333 0.4166666 0.1458333 0.3333333 0.1666666 0.4166666 0.1458333 0.5 0.1458333 0.4166666 0.1875 0.5 0.1666666 0.5833333 0.1666666 0.5 0.1875 0.5833333 0.1666666 0.6666667 0.1666666 0.5833333 0.1666666 0.6666667 0.1875 0.75 0.1666666 0.75 0.1875 0.75 0.1666666 0.8333333 0.1666666 0.75 0.1875 0.8333333 0.1666666 0.9166667 0.1666666 0.8333333 0.1875 0.9166667 0.1666666 1 0.1666666 0.9166667 0.1666666 0 0.1875 0.08333331 0.1666666 0.08333331 0.1666666 0.08333331 0.1875 0.1666666 0.1666666 0.1666666 0.1666666 0.1666666 0.1875 0.25 0.1666666 0.25 0.1875 0.25 0.1666666 0.3333333 0.1666666 0.25 0.1875 0.3333333 0.1666666 0.4166666 0.1666666 0.3333333 0.1875 0.4166666 0.1666666 0.5 0.1666666 0.4166666 0.1875 0.5 0.2083333 0.5833333 0.1875 0.5833333 0.2083333 0.5833333 0.1875 0.6666667 0.1875 0.5833333 0.2083333 0.6666667 0.1875 0.75 0.1875 0.6666667 0.1875 0.75 0.2083333 0.8333333 0.1875 0.8333333 0.1875 0.8333333 0.2083333 0.9166667 0.1875 0.9166667 0.2083333 0.9166667 0.1875 1 0.1875 0.9166667 0.2083333 0 0.1875 0.08333331 0.1875 0 0.2083333 0.08333331 0.1875 0.1666666 0.1875 0.08333331 0.2083333 0.1666666 0.1875 0.25 0.1875 0.1666666 0.1875 0.25 0.2083333 0.3333333 0.1875 0.3333333 0.1875 0.3333333 0.2083333 0.4166666 0.1875 0.4166666 0.2083333 0.4166666 0.1875 0.5 0.1875 0.4166666 0.2083333 0.5 0.2291666 0.5833333 0.2083333 0.5833333 0.2291666 0.5833333 0.2083333 0.6666667 0.2083333 0.5833333 0.2291666 0.6666667 0.2083333 0.75 0.2083333 0.6666667 0.2291666 0.75 0.2083333 0.8333333 0.2083333 0.75 0.2083333 0.8333333 0.2291666 0.9166667 0.2083333 0.9166667 0.2291666 0.9166667 0.2083333 1 0.2083333 0.9166667 0.2083333 0 0.2291666 0.08333331 0.2083333 0.08333331 0.2291666 0.08333331 0.2083333 0.1666666 0.2083333 0.08333331 0.2083333 0.1666666 0.2291666 0.25 0.2083333 0.25 0.2291666 0.25 0.2083333 0.3333333 0.2083333 0.25 0.2291666 0.3333333 0.2083333 0.4166666 0.2083333 0.3333333 0.2291666 0.4166666 0.2083333 0.5 0.2083333 0.4166666 0.25 0.5 0.2291666 0.5833333 0.2291666 0.5 0.25 0.5833333 0.2291666 0.6666667 0.2291666 0.5833333 0.25 0.6666667 0.2291666 0.75 0.2291666 0.6666667 0.2291666 0.75 0.25 0.8333333 0.2291666 0.8333333 0.25 0.8333333 0.2291666 0.9166667 0.2291666 0.8333333 0.2291666 0.9166667 0.25 1 0.2291666 1 0.25 0 0.2291666 0.08333331 0.2291666 0 0.25 0.08333331 0.2291666 0.1666666 0.2291666 0.08333331 0.25 0.1666666 0.2291666 0.25 0.2291666 0.1666666 0.25 0.25 0.2291666 0.3333333 0.2291666 0.25 0.2291666 0.3333333 0.25 0.4166666 0.2291666 0.4166666 0.25 0.4166666 0.2291666 0.5 0.2291666 0.4166666 0.2708333 0.5 0.25 0.5833333 0.25 0.5 0.2708333 0.5833333 0.25 0.6666667 0.25 0.5833333 0.25 0.6666667 0.2708333 0.75 0.25 0.75 0.2708333 0.75 0.25 0.8333333 0.25 0.75 0.2708333 0.8333333 0.25 0.9166667 0.25 0.8333333 0.2708333 0.9166667 0.25 1 0.25 0.9166667 0.2708333 0 0.25 0.08333331 0.25 0 0.25 0.08333331 0.2708333 0.1666666 0.25 0.1666666 0.25 0.1666666 0.2708333 0.25 0.25 0.25 0.2708333 0.25 0.25 0.3333333 0.25 0.25 0.2708333 0.3333333 0.25 0.4166666 0.25 0.3333333 0.2708333 0.4166666 0.25 0.5 0.25 0.4166666 0.2916666 0.5 0.2708333 0.5833333 0.2708333 0.5 0.2916666 0.5833333 0.2708333 0.6666667 0.2708333 0.5833333 0.2916666 0.6666667 0.2708333 0.75 0.2708333 0.6666667 0.2916666 0.75 0.2708333 0.8333333 0.2708333 0.75 0.2708333 0.8333333 0.2916666 0.9166667 0.2708333 0.9166667 0.2916666 0.9166667 0.2708333 1 0.2708333 0.9166667 0.2916666 0 0.2708333 0.08333331 0.2708333 0 0.2916666 0.08333331 0.2708333 0.1666666 0.2708333 0.08333331 0.2708333 0.1666666 0.2916666 0.25 0.2708333 0.25 0.2708333 0.25 0.2916666 0.3333333 0.2708333 0.3333333 0.2708333 0.3333333 0.2916666 0.4166666 0.2708333 0.4166666 0.2916666 0.4166666 0.2708333 0.5 0.2708333 0.4166666 0.3125 0.5 0.2916666 0.5833333 0.2916666 0.5 0.3125 0.5833333 0.2916666 0.6666667 0.2916666 0.5833333 0.3125 0.6666667 0.2916666 0.75 0.2916666 0.6666667 0.2916666 0.75 0.3125 0.8333333 0.2916666 0.8333333 0.3125 0.8333333 0.2916666 0.9166667 0.2916666 0.8333333 0.2916666 0.9166667 0.3125 1 0.2916666 1 0.3125 0 0.2916666 0.08333331 0.2916666 0 0.3125 0.08333331 0.2916666 0.1666666 0.2916666 0.08333331 0.3125 0.1666666 0.2916666 0.25 0.2916666 0.1666666 0.3125 0.25 0.2916666 0.3333333 0.2916666 0.25 0.2916666 0.3333333 0.3125 0.4166666 0.2916666 0.4166666 0.2916666 0.4166666 0.3125 0.5 0.2916666 0.5 0.3333333 0.5 0.3125 0.5833333 0.3125 0.5 0.3125 0.5833333 0.3333333 0.6666667 0.3125 0.6666667 0.3125 0.6666667 0.3333333 0.75 0.3125 0.75 0.3125 0.75 0.3333333 0.8333333 0.3125 0.8333333 0.3125 0.8333333 0.3333333 0.9166667 0.3125 0.9166667 0.3125 0.9166667 0.3333333 1 0.3125 1 0.3333333 0 0.3125 0.08333331 0.3125 0 0.3333333 0.08333331 0.3125 0.1666666 0.3125 0.08333331 0.3333333 0.1666666 0.3125 0.25 0.3125 0.1666666 0.3333333 0.25 0.3125 0.3333333 0.3125 0.25 0.3333333 0.3333333 0.3125 0.4166666 0.3125 0.3333333 0.3333333 0.4166666 0.3125 0.5 0.3125 0.4166666 0.3333333 0.5 0.3541666 0.5833333 0.3333333 0.5833333 0.3541666 0.5833333 0.3333333 0.6666667 0.3333333 0.5833333 0.3541666 0.6666667 0.3333333 0.75 0.3333333 0.6666667 0.3541666 0.75 0.3333333 0.8333333 0.3333333 0.75 0.3541666 0.8333333 0.3333333 0.9166667 0.3333333 0.8333333 0.3541666 0.9166667 0.3333333 1 0.3333333 0.9166667 0.3333333 0 0.3541666 0.08333331 0.3333333 0.08333331 0.3333333 0.08333331 0.3541666 0.1666666 0.3333333 0.1666666 0.3333333 0.1666666 0.3541666 0.25 0.3333333 0.25 0.3333333 0.25 0.3541666 0.3333333 0.3333333 0.3333333 0.3333333 0.3333333 0.3541666 0.4166666 0.3333333 0.4166666 0.3541666 0.4166666 0.3333333 0.5 0.3333333 0.4166666 0.3541666 0.5 0.375 0.5833333 0.3541666 0.5833333 0.375 0.5833333 0.3541666 0.6666667 0.3541666 0.5833333 0.3541666 0.6666667 0.375 0.75 0.3541666 0.75 0.3541666 0.75 0.375 0.8333333 0.3541666 0.8333333 0.3541666 0.8333333 0.375 0.9166667 0.3541666 0.9166667 0.3541666 0.9166667 0.375 1 0.3541666 1 0.375 0 0.3541666 0.08333331 0.3541666 0 0.375 0.08333331 0.3541666 0.1666666 0.3541666 0.08333331 0.375 0.1666666 0.3541666 0.25 0.3541666 0.1666666 0.375 0.25 0.3541666 0.3333333 0.3541666 0.25 0.375 0.3333333 0.3541666 0.4166666 0.3541666 0.3333333 0.375 0.4166666 0.3541666 0.5 0.3541666 0.4166666 0.375 0.5 0.3958333 0.5833333 0.375 0.5833333 0.3958333 0.5833333 0.375 0.6666667 0.375 0.5833333 0.375 0.6666667 0.3958333 0.75 0.375 0.75 0.3958333 0.75 0.375 0.8333333 0.375 0.75 0.3958333 0.8333333 0.375 0.9166667 0.375 0.8333333 0.375 0.9166667 0.3958333 1 0.375 1 0.3958333 0 0.375 0.08333331 0.375 0 0.375 0.08333331 0.3958333 0.1666666 0.375 0.1666666 0.3958333 0.1666666 0.375 0.25 0.375 0.1666666 0.3958333 0.25 0.375 0.3333333 0.375 0.25 0.375 0.3333333 0.3958333 0.4166666 0.375 0.4166666 0.3958333 0.4166666 0.375 0.5 0.375 0.4166666 0.3958333 0.5 0.4166666 0.5833333 0.3958333 0.5833333 0.4166666 0.5833333 0.3958333 0.6666667 0.3958333 0.5833333 0.4166666 0.6666667 0.3958333 0.75 0.3958333 0.6666667 0.3958333 0.75 0.4166666 0.8333333 0.3958333 0.8333333 0.4166666 0.8333333 0.3958333 0.9166667 0.3958333 0.8333333 0.3958333 0.9166667 0.4166666 1 0.3958333 1 0.4166666 0 0.3958333 0.08333331 0.3958333 0 0.3958333 0.08333331 0.4166666 0.1666666 0.3958333 0.1666666 0.4166666 0.1666666 0.3958333 0.25 0.3958333 0.1666666 0.4166666 0.25 0.3958333 0.3333333 0.3958333 0.25 0.3958333 0.3333333 0.4166666 0.4166666 0.3958333 0.4166666 0.4166666 0.4166666 0.3958333 0.5 0.3958333 0.4166666 0.4166666 0.5 0.4375 0.5833333 0.4166666 0.5833333 0.4166666 0.5833333 0.4375 0.6666667 0.4166666 0.6666667 0.4166666 0.6666667 0.4375 0.75 0.4166666 0.75 0.4166666 0.75 0.4375 0.8333333 0.4166666 0.8333333 0.4375 0.8333333 0.4166666 0.9166667 0.4166666 0.8333333 0.4166666 0.9166667 0.4375 1 0.4166666 1 0.4375 0 0.4166666 0.08333331 0.4166666 0 0.4375 0.08333331 0.4166666 0.1666666 0.4166666 0.08333331 0.4375 0.1666666 0.4166666 0.25 0.4166666 0.1666666 0.4375 0.25 0.4166666 0.3333333 0.4166666 0.25 0.4375 0.3333333 0.4166666 0.4166666 0.4166666 0.3333333 0.4375 0.4166666 0.4166666 0.5 0.4166666 0.4166666 0.4583333 0.5 0.4375 0.5833333 0.4375 0.5 0.4583333 0.5833333 0.4375 0.6666667 0.4375 0.5833333 0.4583333 0.6666667 0.4375 0.75 0.4375 0.6666667 0.4583333 0.75 0.4375 0.8333333 0.4375 0.75 0.4583333 0.8333333 0.4375 0.9166667 0.4375 0.8333333 0.4583333 0.9166667 0.4375 1 0.4375 0.9166667 0.4375 0 0.4583333 0.08333331 0.4375 0.08333331 0.4375 0.08333331 0.4583333 0.1666666 0.4375 0.1666666 0.4583333 0.1666666 0.4375 0.25 0.4375 0.1666666 0.4375 0.25 0.4583333 0.3333333 0.4375 0.3333333 0.4583333 0.3333333 0.4375 0.4166666 0.4375 0.3333333 0.4375 0.4166666 0.4583333 0.5 0.4375 0.5 0.4791666 0.5 0.4583333 0.5833333 0.4583333 0.5 0.4583333 0.5833333 0.4791666 0.6666667 0.4583333 0.6666667 0.4583333 0.6666667 0.4791666 0.75 0.4583333 0.75 0.4583333 0.75 0.4791666 0.8333333 0.4583333 0.8333333 0.4583333 0.8333333 0.4791666 0.9166667 0.4583333 0.9166667 0.4583333 0.9166667 0.4791666 1 0.4583333 1 0.4791666 0 0.4583333 0.08333331 0.4583333 0 0.4791666 0.08333331 0.4583333 0.1666666 0.4583333 0.08333331 0.4791666 0.1666666 0.4583333 0.25 0.4583333 0.1666666 0.4791666 0.25 0.4583333 0.3333333 0.4583333 0.25 0.4791666 0.3333333 0.4583333 0.4166666 0.4583333 0.3333333 0.4791666 0.4166666 0.4583333 0.5 0.4583333 0.4166666 0.5 0.5 0.4791666 0.5833333 0.4791666 0.5 0.5 0.5833333 0.4791666 0.6666667 0.4791666 0.5833333 0.5 0.6666667 0.4791666 0.75 0.4791666 0.6666667 0.5 0.75 0.4791666 0.8333333 0.4791666 0.75 0.4791666 0.8333333 0.5 0.9166667 0.4791666 0.9166667 0.5 0.9166667 0.4791666 1 0.4791666 0.9166667 0.4791666 0 0.5 0.08333331 0.4791666 0.08333331 0.5 0.08333331 0.4791666 0.1666666 0.4791666 0.08333331 0.4791666 0.1666666 0.5 0.25 0.4791666 0.25 0.4791666 0.25 0.5 0.3333333 0.4791666 0.3333333 0.4791666 0.3333333 0.5 0.4166666 0.4791666 0.4166666 0.4791666 0.4166666 0.5 0.5 0.4791666 0.5 0.5 0.5 0.5208333 0.5 0.5208333 0.5833333 0.5 0.5833333 0.5208333 0.5833333 0.5208333 0.6666667 0.5 0.6666667 0.5208333 0.6666667 0.5208333 0.75 0.5 0.75 0.5208333 0.75 0.5208333 0.8333333 0.5208333 0.8333333 0.5208333 0.9166667 0.5 0.9166667 0.5 0.9166667 0.5208333 0.9166667 0.5208333 1 0.5208333 0 0.5208333 0.08333331 0.5 0.08333331 0.5 0.08333331 0.5208333 0.08333331 0.5208333 0.1666666 0.5208333 0.1666666 0.5208333 0.25 0.5 0.25 0.5208333 0.25 0.5208333 0.3333333 0.5 0.3333333 0.5208333 0.3333333 0.5208333 0.4166666 0.5 0.4166666 0.5208333 0.4166666 0.5208333 0.5 0.5 0.5 0.5416667 0.5 0.5416667 0.5833333 0.5208333 0.5833333 0.5416667 0.5833333 0.5416667 0.6666667 0.5208333 0.6666667 0.5416667 0.6666667 0.5416667 0.75 0.5208333 0.75 0.5416667 0.75 0.5416667 0.8333333 0.5208333 0.8333333 0.5416667 0.8333333 0.5416667 0.9166667 0.5208333 0.9166667 0.5208333 0.9166667 0.5416667 0.9166667 0.5416667 1 0.5416667 0 0.5416667 0.08333331 0.5208333 0.08333331 0.5208333 0.08333331 0.5416667 0.08333331 0.5416667 0.1666666 0.5208333 0.1666666 0.5416667 0.1666666 0.5416667 0.25 0.5208333 0.25 0.5416667 0.25 0.5416667 0.3333333 0.5208333 0.3333333 0.5416667 0.3333333 0.5416667 0.4166666 0.5208333 0.4166666 0.5416667 0.4166666 0.5416667 0.5 0.5416667 0.5 0.5625 0.5 0.5625 0.5833333 0.5625 0.5833333 0.5625 0.6666667 0.5416667 0.6666667 0.5625 0.6666667 0.5625 0.75 0.5416667 0.75 0.5416667 0.75 0.5625 0.75 0.5625 0.8333333 0.5416667 0.8333333 0.5625 0.8333333 0.5625 0.9166667 0.5416667 0.9166667 0.5625 0.9166667 0.5625 1 0.5625 0 0.5625 0.08333331 0.5416667 0.08333331 0.5625 0.08333331 0.5625 0.1666666 0.5416667 0.1666666 0.5625 0.1666666 0.5625 0.25 0.5416667 0.25 0.5416667 0.25 0.5625 0.25 0.5625 0.3333333 0.5625 0.3333333 0.5625 0.4166666 0.5416667 0.4166666 0.5625 0.4166666 0.5625 0.5 0.5416667 0.5 0.5625 0.5 0.5833333 0.5 0.5833333 0.5833333 0.5833333 0.5833333 0.5833333 0.6666667 0.5625 0.6666667 0.5625 0.6666667 0.5833333 0.6666667 0.5833333 0.75 0.5833333 0.75 0.5833333 0.8333333 0.5625 0.8333333 0.5833333 0.8333333 0.5833333 0.9166667 0.5625 0.9166667 0.5833333 0.9166667 0.5833333 1 0.5625 1 0.5625 0 0.5833333 0 0.5833333 0.08333331 0.5833333 0.08333331 0.5833333 0.1666666 0.5625 0.1666666 0.5625 0.1666666 0.5833333 0.1666666 0.5833333 0.25 0.5833333 0.25 0.5833333 0.3333333 0.5625 0.3333333 0.5625 0.3333333 0.5833333 0.3333333 0.5833333 0.4166666 0.5833333 0.4166666 0.5833333 0.5 0.5625 0.5 0.6041667 0.5 0.6041667 0.5833333 0.5833333 0.5833333 0.5833333 0.5833333 0.6041667 0.5833333 0.6041667 0.6666667 0.6041667 0.6666667 0.6041667 0.75 0.5833333 0.75 0.6041667 0.75 0.6041667 0.8333333 0.5833333 0.8333333 0.5833333 0.8333333 0.6041667 0.8333333 0.6041667 0.9166667 0.6041667 0.9166667 0.6041667 1 0.5833333 1 0.5833333 0 0.6041667 0 0.6041667 0.08333331 0.6041667 0.08333331 0.6041667 0.1666666 0.5833333 0.1666666 0.5833333 0.1666666 0.6041667 0.1666666 0.6041667 0.25 0.6041667 0.25 0.6041667 0.3333333 0.5833333 0.3333333 0.6041667 0.3333333 0.6041667 0.4166666 0.5833333 0.4166666 0.5833333 0.4166666 0.6041667 0.4166666 0.6041667 0.5 0.625 0.5 0.625 0.5833333 0.6041667 0.5833333 0.625 0.5833333 0.625 0.6666667 0.6041667 0.6666667 0.625 0.6666667 0.625 0.75 0.6041667 0.75 0.625 0.75 0.625 0.8333333 0.6041667 0.8333333 0.6041667 0.8333333 0.625 0.8333333 0.625 0.9166667 0.625 0.9166667 0.625 1 0.6041667 1 0.625 0 0.625 0.08333331 0.6041667 0.08333331 0.625 0.08333331 0.625 0.1666666 0.6041667 0.1666666 0.6041667 0.1666666 0.625 0.1666666 0.625 0.25 0.6041667 0.25 0.625 0.25 0.625 0.3333333 0.6041667 0.3333333 0.625 0.3333333 0.625 0.4166666 0.6041667 0.4166666 0.625 0.4166666 0.625 0.5 0.625 0.5 0.6458333 0.5 0.6458333 0.5833333 0.625 0.5833333 0.6458333 0.5833333 0.6458333 0.6666667 0.6458333 0.6666667 0.6458333 0.75 0.625 0.75 0.6458333 0.75 0.6458333 0.8333333 0.625 0.8333333 0.6458333 0.8333333 0.6458333 0.9166667 0.625 0.9166667 0.6458333 0.9166667 0.6458333 1 0.625 1 0.625 0 0.6458333 0 0.6458333 0.08333331 0.625 0.08333331 0.6458333 0.08333331 0.6458333 0.1666666 0.625 0.1666666 0.6458333 0.1666666 0.6458333 0.25 0.625 0.25 0.6458333 0.25 0.6458333 0.3333333 0.6458333 0.3333333 0.6458333 0.4166666 0.625 0.4166666 0.6458333 0.4166666 0.6458333 0.5 0.625 0.5 0.6458333 0.5 0.6666667 0.5 0.6666667 0.5833333 0.6458333 0.5833333 0.6666667 0.5833333 0.6666667 0.6666667 0.6458333 0.6666667 0.6666667 0.6666667 0.6666667 0.75 0.6458333 0.75 0.6666667 0.75 0.6666667 0.8333333 0.6458333 0.8333333 0.6666667 0.8333333 0.6666667 0.9166667 0.6458333 0.9166667 0.6666667 0.9166667 0.6666667 1 0.6666667 0 0.6666667 0.08333331 0.6458333 0.08333331 0.6666667 0.08333331 0.6666667 0.1666666 0.6458333 0.1666666 0.6666667 0.1666666 0.6666667 0.25 0.6458333 0.25 0.6666667 0.25 0.6666667 0.3333333 0.6458333 0.3333333 0.6666667 0.3333333 0.6666667 0.4166666 0.6458333 0.4166666 0.6666667 0.4166666 0.6666667 0.5 0.6458333 0.5 0.6875 0.5 0.6875 0.5833333 0.6666667 0.5833333 0.6875 0.5833333 0.6875 0.6666667 0.6666667 0.6666667 0.6875 0.6666667 0.6875 0.75 0.6666667 0.75 0.6875 0.75 0.6875 0.8333333 0.6666667 0.8333333 0.6875 0.8333333 0.6875 0.9166667 0.6666667 0.9166667 0.6875 0.9166667 0.6875 1 0.6666667 1 0.6666667 0 0.6875 0 0.6875 0.08333331 0.6666667 0.08333331 0.6875 0.08333331 0.6875 0.1666666 0.6666667 0.1666666 0.6875 0.1666666 0.6875 0.25 0.6666667 0.25 0.6875 0.25 0.6875 0.3333333 0.6666667 0.3333333 0.6875 0.3333333 0.6875 0.4166666 0.6875 0.4166666 0.6875 0.5 0.6666667 0.5 0.7083333 0.5 0.7083333 0.5833333 0.6875 0.5833333 0.6875 0.5833333 0.7083333 0.5833333 0.7083333 0.6666667 0.6875 0.6666667 0.7083333 0.6666667 0.7083333 0.75 0.7083333 0.75 0.7083333 0.8333333 0.6875 0.8333333 0.6875 0.8333333 0.7083333 0.8333333 0.7083333 0.9166667 0.7083333 0.9166667 0.7083333 1 0.6875 1 0.6875 0 0.7083333 0 0.7083333 0.08333331 0.7083333 0.08333331 0.7083333 0.1666666 0.6875 0.1666666 0.7083333 0.1666666 0.7083333 0.25 0.6875 0.25 0.7083333 0.25 0.7083333 0.3333333 0.6875 0.3333333 0.7083333 0.3333333 0.7083333 0.4166666 0.6875 0.4166666 0.6875 0.4166666 0.7083333 0.4166666 0.7083333 0.5 0.7291667 0.5 0.7291667 0.5833333 0.7083333 0.5833333 0.7083333 0.5833333 0.7291667 0.5833333 0.7291667 0.6666667 0.7291667 0.6666667 0.7291667 0.75 0.7083333 0.75 0.7291667 0.75 0.7291667 0.8333333 0.7083333 0.8333333 0.7291667 0.8333333 0.7291667 0.9166667 0.7083333 0.9166667 0.7291667 0.9166667 0.7291667 1 0.7083333 1 0.7083333 0 0.7291667 0 0.7291667 0.08333331 0.7083333 0.08333331 0.7291667 0.08333331 0.7291667 0.1666666 0.7083333 0.1666666 0.7291667 0.1666666 0.7291667 0.25 0.7291667 0.25 0.7291667 0.3333333 0.7083333 0.3333333 0.7291667 0.3333333 0.7291667 0.4166666 0.7083333 0.4166666 0.7083333 0.4166666 0.7291667 0.4166666 0.7291667 0.5 0.75 0.5 0.75 0.5833333 0.7291667 0.5833333 0.75 0.5833333 0.75 0.6666667 0.7291667 0.6666667 0.75 0.6666667 0.75 0.75 0.7291667 0.75 0.7291667 0.75 0.75 0.75 0.75 0.8333333 0.7291667 0.8333333 0.75 0.8333333 0.75 0.9166667 0.75 0.9166667 0.75 1 0.7291667 1 0.75 0 0.75 0.08333331 0.7291667 0.08333331 0.75 0.08333331 0.75 0.1666666 0.7291667 0.1666666 0.75 0.1666666 0.75 0.25 0.7291667 0.25 0.7291667 0.25 0.75 0.25 0.75 0.3333333 0.75 0.3333333 0.75 0.4166666 0.7291667 0.4166666 0.75 0.4166666 0.75 0.5 0.7291667 0.5 0.7708333 0.5 0.7708333 0.5833333 0.75 0.5833333 0.7708333 0.5833333 0.7708333 0.6666667 0.75 0.6666667 0.7708333 0.6666667 0.7708333 0.75 0.75 0.75 0.7708333 0.75 0.7708333 0.8333333 0.75 0.8333333 0.75 0.8333333 0.7708333 0.8333333 0.7708333 0.9166667 0.7708333 0.9166667 0.7708333 1 0.75 1 0.7708333 0 0.7708333 0.08333331 0.75 0.08333331 0.7708333 0.08333331 0.7708333 0.1666666 0.75 0.1666666 0.75 0.1666666 0.7708333 0.1666666 0.7708333 0.25 0.75 0.25 0.7708333 0.25 0.7708333 0.3333333 0.75 0.3333333 0.7708333 0.3333333 0.7708333 0.4166666 0.75 0.4166666 0.7708333 0.4166666 0.7708333 0.5 0.7708333 0.5 0.7916667 0.5 0.7916667 0.5833333 0.7708333 0.5833333 0.7916667 0.5833333 0.7916667 0.6666667 0.7708333 0.6666667 0.7916667 0.6666667 0.7916667 0.75 0.7708333 0.75 0.7916667 0.75 0.7916667 0.8333333 0.7708333 0.8333333 0.7916667 0.8333333 0.7916667 0.9166667 0.7916667 0.9166667 0.7916667 1 0.7708333 1 0.7708333 0 0.7916667 0 0.7916667 0.08333331 0.7916667 0.08333331 0.7916667 0.1666666 0.7708333 0.1666666 0.7916667 0.1666666 0.7916667 0.25 0.7708333 0.25 0.7916667 0.25 0.7916667 0.3333333 0.7708333 0.3333333 0.7916667 0.3333333 0.7916667 0.4166666 0.7708333 0.4166666 0.7916667 0.4166666 0.7916667 0.5 0.7708333 0.5 0.8125 0.5 0.8125 0.5833333 0.7916667 0.5833333 0.8125 0.5833333 0.8125 0.6666667 0.7916667 0.6666667 0.7916667 0.6666667 0.8125 0.6666667 0.8125 0.75 0.8125 0.75 0.8125 0.8333333 0.7916667 0.8333333 0.8125 0.8333333 0.8125 0.9166667 0.7916667 0.9166667 0.8125 0.9166667 0.8125 1 0.7916667 1 0.7916667 0 0.8125 0 0.8125 0.08333331 0.7916667 0.08333331 0.8125 0.08333331 0.8125 0.1666666 0.7916667 0.1666666 0.8125 0.1666666 0.8125 0.25 0.8125 0.25 0.8125 0.3333333 0.7916667 0.3333333 0.7916667 0.3333333 0.8125 0.3333333 0.8125 0.4166666 0.8125 0.4166666 0.8125 0.5 0.7916667 0.5 0.8333333 0.5 0.8333333 0.5833333 0.8125 0.5833333 0.8333333 0.5833333 0.8333333 0.6666667 0.8125 0.6666667 0.8333333 0.6666667 0.8333333 0.75 0.8125 0.75 0.8125 0.75 0.8333333 0.75 0.8333333 0.8333333 0.8125 0.8333333 0.8333333 0.8333333 0.8333333 0.9166667 0.8125 0.9166667 0.8333333 0.9166667 0.8333333 1 0.8333333 0 0.8333333 0.08333331 0.8125 0.08333331 0.8333333 0.08333331 0.8333333 0.1666666 0.8125 0.1666666 0.8333333 0.1666666 0.8333333 0.25 0.8125 0.25 0.8125 0.25 0.8333333 0.25 0.8333333 0.3333333 0.8333333 0.3333333 0.8333333 0.4166666 0.8125 0.4166666 0.8333333 0.4166666 0.8333333 0.5 0.8125 0.5 0.8541667 0.5 0.8541667 0.5833333 0.8333333 0.5833333 0.8541667 0.5833333 0.8541667 0.6666667 0.8333333 0.6666667 0.8541667 0.6666667 0.8541667 0.75 0.8333333 0.75 0.8541667 0.75 0.8541667 0.8333333 0.8333333 0.8333333 0.8541667 0.8333333 0.8541667 0.9166667 0.8333333 0.9166667 0.8333333 0.9166667 0.8541667 0.9166667 0.8541667 1 0.8541667 0 0.8541667 0.08333331 0.8333333 0.08333331 0.8333333 0.08333331 0.8541667 0.08333331 0.8541667 0.1666666 0.8333333 0.1666666 0.8541667 0.1666666 0.8541667 0.25 0.8333333 0.25 0.8541667 0.25 0.8541667 0.3333333 0.8333333 0.3333333 0.8541667 0.3333333 0.8541667 0.4166666 0.8333333 0.4166666 0.8541667 0.4166666 0.8541667 0.5 0.8541667 0.5 0.875 0.5 0.875 0.5833333 0.875 0.5833333 0.875 0.6666667 0.8541667 0.6666667 0.8541667 0.6666667 0.875 0.6666667 0.875 0.75 0.875 0.75 0.875 0.8333333 0.8541667 0.8333333 0.875 0.8333333 0.875 0.9166667 0.8541667 0.9166667 0.8541667 0.9166667 0.875 0.9166667 0.875 1 0.875 0 0.875 0.08333331 0.8541667 0.08333331 0.8541667 0.08333331 0.875 0.08333331 0.875 0.1666666 0.8541667 0.1666666 0.875 0.1666666 0.875 0.25 0.875 0.25 0.875 0.3333333 0.8541667 0.3333333 0.875 0.3333333 0.875 0.4166666 0.8541667 0.4166666 0.875 0.4166666 0.875 0.5 0.8541667 0.5 0.875 0.5 0.8958333 0.5 0.8958333 0.5833333 0.8958333 0.5833333 0.8958333 0.6666667 0.875 0.6666667 0.8958333 0.6666667 0.8958333 0.75 0.875 0.75 0.875 0.75 0.8958333 0.75 0.8958333 0.8333333 0.875 0.8333333 0.8958333 0.8333333 0.8958333 0.9166667 0.875 0.9166667 0.8958333 0.9166667 0.8958333 1 0.8958333 0 0.8958333 0.08333331 0.875 0.08333331 0.8958333 0.08333331 0.8958333 0.1666666 0.875 0.1666666 0.8958333 0.1666666 0.8958333 0.25 0.875 0.25 0.875 0.25 0.8958333 0.25 0.8958333 0.3333333 0.875 0.3333333 0.8958333 0.3333333 0.8958333 0.4166666 0.8958333 0.4166666 0.8958333 0.5 0.875 0.5 0.8958333 0.5 0.9166667 0.5 0.9166667 0.5833333 0.9166667 0.5833333 0.9166667 0.6666667 0.8958333 0.6666667 0.8958333 0.6666667 0.9166667 0.6666667 0.9166667 0.75 0.9166667 0.75 0.9166667 0.8333333 0.8958333 0.8333333 0.9166667 0.8333333 0.9166667 0.9166667 0.8958333 0.9166667 0.9166667 0.9166667 0.9166667 1 0.8958333 1 0.8958333 0 0.9166667 0 0.9166667 0.08333331 0.8958333 0.08333331 0.9166667 0.08333331 0.9166667 0.1666666 0.9166667 0.1666666 0.9166667 0.25 0.8958333 0.25 0.9166667 0.25 0.9166667 0.3333333 0.8958333 0.3333333 0.8958333 0.3333333 0.9166667 0.3333333 0.9166667 0.4166666 0.9166667 0.4166666 0.9166667 0.5 0.8958333 0.5 0.9166667 0.5 0.9375 0.5 0.9375 0.5833333 0.9375 0.5833333 0.9375 0.6666667 0.9166667 0.6666667 0.9166667 0.6666667 0.9375 0.6666667 0.9375 0.75 0.9166667 0.75 0.9375 0.75 0.9375 0.8333333 0.9375 0.8333333 0.9375 0.9166667 0.9166667 0.9166667 0.9375 0.9166667 0.9375 1 0.9166667 1 0.9166667 0 0.9375 0 0.9375 0.08333331 0.9375 0.08333331 0.9375 0.1666666 0.9166667 0.1666666 0.9375 0.1666666 0.9375 0.25 0.9166667 0.25 0.9375 0.25 0.9375 0.3333333 0.9166667 0.3333333 0.9166667 0.3333333 0.9375 0.3333333 0.9375 0.4166666 0.9375 0.4166666 0.9375 0.5 0.9166667 0.5 0.9583333 0.5 0.9583333 0.5833333 0.9375 0.5833333 0.9375 0.5833333 0.9583333 0.5833333 0.9583333 0.6666667 0.9583333 0.6666667 0.9583333 0.75 0.9375 0.75 0.9375 0.75 0.9583333 0.75 0.9583333 0.8333333 0.9375 0.8333333 0.9583333 0.8333333 0.9583333 0.9166667 0.9375 0.9166667 0.9583333 0.9166667 0.9583333 1 0.9583333 0 0.9583333 0.08333331 0.9375 0.08333331 0.9583333 0.08333331 0.9583333 0.1666666 0.9375 0.1666666 0.9583333 0.1666666 0.9583333 0.25 0.9375 0.25 0.9583333 0.25 0.9583333 0.3333333 0.9375 0.3333333 0.9583333 0.3333333 0.9583333 0.4166666 0.9375 0.4166666 0.9583333 0.4166666 0.9583333 0.5 0.9375 0.5 0.9791667 0.5 0.9791667 0.5833333 0.9583333 0.5833333 0.9791667 0.5833333 0.9791667 0.6666667 0.9583333 0.6666667 0.9791667 0.6666667 0.9791667 0.75 0.9583333 0.75 0.9791667 0.75 0.9791667 0.8333333 0.9583333 0.8333333 0.9791667 0.8333333 0.9791667 0.9166667 0.9583333 0.9166667 0.9583333 0.9166667 0.9791667 0.9166667 0.9791667 1 0.9791667 0 0.9791667 0.08333331 0.9583333 0.08333331 0.9583333 0.08333331 0.9791667 0.08333331 0.9791667 0.1666666 0.9583333 0.1666666 0.9791667 0.1666666 0.9791667 0.25 0.9583333 0.25 0.9791667 0.25 0.9791667 0.3333333 0.9583333 0.3333333 0.9791667 0.3333333 0.9791667 0.4166666 0.9583333 0.4166666 0.9791667 0.4166666 0.9791667 0.5 0.9791667 0.5 1 0.5 1 0.5833333 0.9791667 0.5833333 1 0.5833333 1 0.6666667 0.9791667 0.6666667 1 0.6666667 1 0.75 1 0.75 1 0.8333333 0.9791667 0.8333333 1 0.8333333 1 0.9166667 0.9791667 0.9166667 1 0.9166667 1 1 0.9791667 1 1 0 1 0.08333331 0.9791667 0.08333331 0.9791667 0.08333331 1 0.08333331 1 0.1666666 1 0.1666666 1 0.25 0.9791667 0.25 1 0.25 1 0.3333333 0.9791667 0.3333333 1 0.3333333 1 0.4166666 0.9791667 0.4166666 1 0.4166666 1 0.5 0.9791667 0.5 0.02083331 0.5 0.02083331 0.5833333 0 0.5833333 0.02083331 0.5833333 0.02083331 0.6666667 0 0.6666667 0.02083331 0.6666667 0.02083331 0.75 0 0.75 0.02083331 0.75 0.02083331 0.8333333 0 0.8333333 0 0.8333333 0.02083331 0.8333333 0.02083331 0.9166667 0.02083331 0.9166667 0.02083331 1 0 1 0.02083331 0 0.02083331 0.08333331 0 0.08333331 0.02083331 0.08333331 0.02083331 0.1666666 0 0.1666666 0 0.1666666 0.02083331 0.1666666 0.02083331 0.25 0 0.25 0.02083331 0.25 0.02083331 0.3333333 0 0.3333333 0.02083331 0.3333333 0.02083331 0.4166666 0 0.4166666 0.02083331 0.4166666 0.02083331 0.5 0.02083331 0.5 0.04166662 0.5 0.04166662 0.5833333 0.02083331 0.5833333 0.04166662 0.5833333 0.04166662 0.6666667 0.02083331 0.6666667 0.04166662 0.6666667 0.04166662 0.75 0.02083331 0.75 0.04166662 0.75 0.04166662 0.8333333 0.02083331 0.8333333 0.04166662 0.8333333 0.04166662 0.9166667 0.04166662 0.9166667 0.04166662 1 0.02083331 1 0.02083331 0 0.04166662 0 0.04166662 0.08333331 0.04166662 0.08333331 0.04166662 0.1666666 0.02083331 0.1666666 0.04166662 0.1666666 0.04166662 0.25 0.02083331 0.25 0.04166662 0.25 0.04166662 0.3333333 0.02083331 0.3333333 0.04166662 0.3333333 0.04166662 0.4166666 0.02083331 0.4166666 0.04166662 0.4166666 0.04166662 0.5 0.02083331 0.5 0.0625 0.5 0.0625 0.5833333 0.04166662 0.5833333 0.0625 0.5833333 0.0625 0.6666667 0.04166662 0.6666667 0.04166662 0.6666667 0.0625 0.6666667 0.0625 0.75 0.0625 0.75 0.0625 0.8333333 0.04166662 0.8333333 0.0625 0.8333333 0.0625 0.9166667 0.04166662 0.9166667 0.0625 0.9166667 0.0625 1 0.04166662 1 0.04166662 0 0.0625 0 0.0625 0.08333331 0.04166662 0.08333331 0.0625 0.08333331 0.0625 0.1666666 0.04166662 0.1666666 0.0625 0.1666666 0.0625 0.25 0.0625 0.25 0.0625 0.3333333 0.04166662 0.3333333 0.04166662 0.3333333 0.0625 0.3333333 0.0625 0.4166666 0.0625 0.4166666 0.0625 0.5 0.04166662 0.5 0.08333331 0.5 0.08333331 0.5833333 0.0625 0.5833333 0.08333331 0.5833333 0.08333331 0.6666667 0.0625 0.6666667 0.08333331 0.6666667 0.08333331 0.75 0.0625 0.75 0.08333331 0.75 0.08333331 0.8333333 0.0625 0.8333333 0.08333331 0.8333333 0.08333331 0.9166667 0.0625 0.9166667 0.0625 0.9166667 0.08333331 0.9166667 0.08333331 1 0.08333331 0 0.08333331 0.08333331 0.0625 0.08333331 0.0625 0.08333331 0.08333331 0.08333331 0.08333331 0.1666666 0.08333331 0.1666666 0.08333331 0.25 0.0625 0.25 0.0625 0.25 0.08333331 0.25 0.08333331 0.3333333 0.0625 0.3333333 0.08333331 0.3333333 0.08333331 0.4166666 0.0625 0.4166666 0.08333331 0.4166666 0.08333331 0.5 0.1041666 0.5 0.1041666 0.5833333 0.08333331 0.5833333 0.1041666 0.5833333 0.1041666 0.6666667 0.08333331 0.6666667 0.1041666 0.6666667 0.1041666 0.75 0.08333331 0.75 0.1041666 0.75 0.1041666 0.8333333 0.08333331 0.8333333 0.08333331 0.8333333 0.1041666 0.8333333 0.1041666 0.9166667 0.08333331 0.9166667 0.1041666 0.9166667 0.1041666 1 0.1041666 0 0.1041666 0.08333331 0.08333331 0.08333331 0.1041666 0.08333331 0.1041666 0.1666666 0.08333331 0.1666666 0.1041666 0.1666666 0.1041666 0.25 0.08333331 0.25 0.08333331 0.25 0.1041666 0.25 0.1041666 0.3333333 0.08333331 0.3333333 0.1041666 0.3333333 0.1041666 0.4166666 0.08333331 0.4166666 0.1041666 0.4166666 0.1041666 0.5 0.125 0.5 0.125 0.5833333 0.1041666 0.5833333 0.1041666 0.5833333 0.125 0.5833333 0.125 0.6666667 0.1041666 0.6666667 0.125 0.6666667 0.125 0.75 0.125 0.75 0.125 0.8333333 0.1041666 0.8333333 0.125 0.8333333 0.125 0.9166667 0.1041666 0.9166667 0.125 0.9166667 0.125 1 0.1041666 1 0.1041666 0 0.125 0 0.125 0.08333331 0.1041666 0.08333331 0.125 0.08333331 0.125 0.1666666 0.1041666 0.1666666 0.125 0.1666666 0.125 0.25 0.125 0.25 0.125 0.3333333 0.1041666 0.3333333 0.125 0.3333333 0.125 0.4166666 0.1041666 0.4166666 0.1041666 0.4166666 0.125 0.4166666 0.125 0.5 0.1458333 0.5 0.1458333 0.5833333 0.125 0.5833333 0.125 0.5833333 0.1458333 0.5833333 0.1458333 0.6666667 0.125 0.6666667 0.1458333 0.6666667 0.1458333 0.75 0.125 0.75 0.1458333 0.75 0.1458333 0.8333333 0.125 0.8333333 0.1458333 0.8333333 0.1458333 0.9166667 0.1458333 0.9166667 0.1458333 1 0.125 1 0.1458333 0 0.1458333 0.08333331 0.125 0.08333331 0.1458333 0.08333331 0.1458333 0.1666666 0.125 0.1666666 0.1458333 0.1666666 0.1458333 0.25 0.125 0.25 0.1458333 0.25 0.1458333 0.3333333 0.125 0.3333333 0.1458333 0.3333333 0.1458333 0.4166666 0.125 0.4166666 0.1458333 0.4166666 0.1458333 0.5 0.125 0.5 0.1458333 0.5 0.1666666 0.5 0.1666666 0.5833333 0.1666666 0.5833333 0.1666666 0.6666667 0.1458333 0.6666667 0.1458333 0.6666667 0.1666666 0.6666667 0.1666666 0.75 0.1458333 0.75 0.1666666 0.75 0.1666666 0.8333333 0.1458333 0.8333333 0.1666666 0.8333333 0.1666666 0.9166667 0.1666666 0.9166667 0.1666666 1 0.1458333 1 0.1458333 0 0.1666666 0 0.1666666 0.08333331 0.1666666 0.08333331 0.1666666 0.1666666 0.1458333 0.1666666 0.1666666 0.1666666 0.1666666 0.25 0.1458333 0.25 0.1666666 0.25 0.1666666 0.3333333 0.1458333 0.3333333 0.1666666 0.3333333 0.1666666 0.4166666 0.1458333 0.4166666 0.1666666 0.4166666 0.1666666 0.5 0.1458333 0.5 0.1875 0.5 0.1875 0.5833333 0.1666666 0.5833333 0.1875 0.5833333 0.1875 0.6666667 0.1666666 0.6666667 0.1666666 0.6666667 0.1875 0.6666667 0.1875 0.75 0.1875 0.75 0.1875 0.8333333 0.1666666 0.8333333 0.1875 0.8333333 0.1875 0.9166667 0.1666666 0.9166667 0.1875 0.9166667 0.1875 1 0.1666666 1 0.1666666 0 0.1875 0 0.1875 0.08333331 0.1666666 0.08333331 0.1875 0.08333331 0.1875 0.1666666 0.1666666 0.1666666 0.1875 0.1666666 0.1875 0.25 0.1875 0.25 0.1875 0.3333333 0.1666666 0.3333333 0.1875 0.3333333 0.1875 0.4166666 0.1666666 0.4166666 0.1875 0.4166666 0.1875 0.5 0.1666666 0.5 0.1875 0.5 0.2083333 0.5 0.2083333 0.5833333 0.2083333 0.5833333 0.2083333 0.6666667 0.1875 0.6666667 0.2083333 0.6666667 0.2083333 0.75 0.1875 0.75 0.1875 0.75 0.2083333 0.75 0.2083333 0.8333333 0.1875 0.8333333 0.2083333 0.8333333 0.2083333 0.9166667 0.2083333 0.9166667 0.2083333 1 0.1875 1 0.2083333 0 0.2083333 0.08333331 0.1875 0.08333331 0.2083333 0.08333331 0.2083333 0.1666666 0.1875 0.1666666 0.2083333 0.1666666 0.2083333 0.25 0.1875 0.25 0.1875 0.25 0.2083333 0.25 0.2083333 0.3333333 0.1875 0.3333333 0.2083333 0.3333333 0.2083333 0.4166666 0.2083333 0.4166666 0.2083333 0.5 0.1875 0.5 0.2083333 0.5 0.2291666 0.5 0.2291666 0.5833333 0.2291666 0.5833333 0.2291666 0.6666667 0.2083333 0.6666667 0.2291666 0.6666667 0.2291666 0.75 0.2083333 0.75 0.2291666 0.75 0.2291666 0.8333333 0.2083333 0.8333333 0.2083333 0.8333333 0.2291666 0.8333333 0.2291666 0.9166667 0.2291666 0.9166667 0.2291666 1 0.2083333 1 0.2083333 0 0.2291666 0 0.2291666 0.08333331 0.2291666 0.08333331 0.2291666 0.1666666 0.2083333 0.1666666 0.2083333 0.1666666 0.2291666 0.1666666 0.2291666 0.25 0.2291666 0.25 0.2291666 0.3333333 0.2083333 0.3333333 0.2291666 0.3333333 0.2291666 0.4166666 0.2083333 0.4166666 0.2291666 0.4166666 0.2291666 0.5 0.2083333 0.5 0.25 0.5 0.25 0.5833333 0.2291666 0.5833333 0.25 0.5833333 0.25 0.6666667 0.2291666 0.6666667 0.25 0.6666667 0.25 0.75 0.2291666 0.75 0.2291666 0.75 0.25 0.75 0.25 0.8333333 0.25 0.8333333 0.25 0.9166667 0.2291666 0.9166667 0.2291666 0.9166667 0.25 0.9166667 0.25 1 0.25 0 0.25 0.08333331 0.2291666 0.08333331 0.25 0.08333331 0.25 0.1666666 0.2291666 0.1666666 0.25 0.1666666 0.25 0.25 0.2291666 0.25 0.25 0.25 0.25 0.3333333 0.2291666 0.3333333 0.2291666 0.3333333 0.25 0.3333333 0.25 0.4166666 0.25 0.4166666 0.25 0.5 0.2291666 0.5 0.2708333 0.5 0.2708333 0.5833333 0.25 0.5833333 0.2708333 0.5833333 0.2708333 0.6666667 0.25 0.6666667 0.25 0.6666667 0.2708333 0.6666667 0.2708333 0.75 0.2708333 0.75 0.2708333 0.8333333 0.25 0.8333333 0.2708333 0.8333333 0.2708333 0.9166667 0.25 0.9166667 0.2708333 0.9166667 0.2708333 1 0.25 1 0.2708333 0 0.2708333 0.08333331 0.25 0.08333331 0.25 0.08333331 0.2708333 0.08333331 0.2708333 0.1666666 0.25 0.1666666 0.2708333 0.1666666 0.2708333 0.25 0.2708333 0.25 0.2708333 0.3333333 0.25 0.3333333 0.2708333 0.3333333 0.2708333 0.4166666 0.25 0.4166666 0.2708333 0.4166666 0.2708333 0.5 0.25 0.5 0.2916666 0.5 0.2916666 0.5833333 0.2708333 0.5833333 0.2916666 0.5833333 0.2916666 0.6666667 0.2708333 0.6666667 0.2916666 0.6666667 0.2916666 0.75 0.2708333 0.75 0.2916666 0.75 0.2916666 0.8333333 0.2708333 0.8333333 0.2708333 0.8333333 0.2916666 0.8333333 0.2916666 0.9166667 0.2916666 0.9166667 0.2916666 1 0.2708333 1 0.2916666 0 0.2916666 0.08333331 0.2708333 0.08333331 0.2916666 0.08333331 0.2916666 0.1666666 0.2708333 0.1666666 0.2708333 0.1666666 0.2916666 0.1666666 0.2916666 0.25 0.2708333 0.25 0.2916666 0.25 0.2916666 0.3333333 0.2708333 0.3333333 0.2916666 0.3333333 0.2916666 0.4166666 0.2916666 0.4166666 0.2916666 0.5 0.2708333 0.5 0.3125 0.5 0.3125 0.5833333 0.2916666 0.5833333 0.3125 0.5833333 0.3125 0.6666667 0.2916666 0.6666667 0.3125 0.6666667 0.3125 0.75 0.2916666 0.75 0.2916666 0.75 0.3125 0.75 0.3125 0.8333333 0.3125 0.8333333 0.3125 0.9166667 0.2916666 0.9166667 0.2916666 0.9166667 0.3125 0.9166667 0.3125 1 0.3125 0 0.3125 0.08333331 0.2916666 0.08333331 0.3125 0.08333331 0.3125 0.1666666 0.2916666 0.1666666 0.3125 0.1666666 0.3125 0.25 0.2916666 0.25 0.3125 0.25 0.3125 0.3333333 0.2916666 0.3333333 0.2916666 0.3333333 0.3125 0.3333333 0.3125 0.4166666 0.2916666 0.4166666 0.3125 0.4166666 0.3125 0.5 0.3333333 0.5 0.3333333 0.5833333 0.3125 0.5833333 0.3125 0.5833333 0.3333333 0.5833333 0.3333333 0.6666667 0.3125 0.6666667 0.3333333 0.6666667 0.3333333 0.75 0.3125 0.75 0.3333333 0.75 0.3333333 0.8333333 0.3125 0.8333333 0.3333333 0.8333333 0.3333333 0.9166667 0.3125 0.9166667 0.3333333 0.9166667 0.3333333 1 0.3333333 0 0.3333333 0.08333331 0.3125 0.08333331 0.3333333 0.08333331 0.3333333 0.1666666 0.3125 0.1666666 0.3333333 0.1666666 0.3333333 0.25 0.3125 0.25 0.3333333 0.25 0.3333333 0.3333333 0.3125 0.3333333 0.3333333 0.3333333 0.3333333 0.4166666 0.3125 0.4166666 0.3333333 0.4166666 0.3333333 0.5 0.3125 0.5 0.3333333 0.5 0.3541666 0.5 0.3541666 0.5833333 0.3541666 0.5833333 0.3541666 0.6666667 0.3333333 0.6666667 0.3541666 0.6666667 0.3541666 0.75 0.3333333 0.75 0.3541666 0.75 0.3541666 0.8333333 0.3333333 0.8333333 0.3541666 0.8333333 0.3541666 0.9166667 0.3333333 0.9166667 0.3541666 0.9166667 0.3541666 1 0.3333333 1 0.3333333 0 0.3541666 0 0.3541666 0.08333331 0.3333333 0.08333331 0.3541666 0.08333331 0.3541666 0.1666666 0.3333333 0.1666666 0.3541666 0.1666666 0.3541666 0.25 0.3333333 0.25 0.3541666 0.25 0.3541666 0.3333333 0.3333333 0.3333333 0.3541666 0.3333333 0.3541666 0.4166666 0.3541666 0.4166666 0.3541666 0.5 0.3333333 0.5 0.3541666 0.5 0.375 0.5 0.375 0.5833333 0.375 0.5833333 0.375 0.6666667 0.3541666 0.6666667 0.3541666 0.6666667 0.375 0.6666667 0.375 0.75 0.3541666 0.75 0.375 0.75 0.375 0.8333333 0.3541666 0.8333333 0.375 0.8333333 0.375 0.9166667 0.3541666 0.9166667 0.375 0.9166667 0.375 1 0.375 0 0.375 0.08333331 0.3541666 0.08333331 0.375 0.08333331 0.375 0.1666666 0.3541666 0.1666666 0.375 0.1666666 0.375 0.25 0.3541666 0.25 0.375 0.25 0.375 0.3333333 0.3541666 0.3333333 0.375 0.3333333 0.375 0.4166666 0.3541666 0.4166666 0.375 0.4166666 0.375 0.5 0.3541666 0.5 0.375 0.5 0.3958333 0.5 0.3958333 0.5833333 0.3958333 0.5833333 0.3958333 0.6666667 0.375 0.6666667 0.375 0.6666667 0.3958333 0.6666667 0.3958333 0.75 0.3958333 0.75 0.3958333 0.8333333 0.375 0.8333333 0.3958333 0.8333333 0.3958333 0.9166667 0.375 0.9166667 0.375 0.9166667 0.3958333 0.9166667 0.3958333 1 0.3958333 0 0.3958333 0.08333331 0.375 0.08333331 0.375 0.08333331 0.3958333 0.08333331 0.3958333 0.1666666 0.3958333 0.1666666 0.3958333 0.25 0.375 0.25 0.3958333 0.25 0.3958333 0.3333333 0.375 0.3333333 0.375 0.3333333 0.3958333 0.3333333 0.3958333 0.4166666 0.3958333 0.4166666 0.3958333 0.5 0.375 0.5 0.3958333 0.5 0.4166666 0.5 0.4166666 0.5833333 0.4166666 0.5833333 0.4166666 0.6666667 0.3958333 0.6666667 0.4166666 0.6666667 0.4166666 0.75 0.3958333 0.75 0.3958333 0.75 0.4166666 0.75 0.4166666 0.8333333 0.4166666 0.8333333 0.4166666 0.9166667 0.3958333 0.9166667 0.3958333 0.9166667 0.4166666 0.9166667 0.4166666 1 0.4166666 0 0.4166666 0.08333331 0.3958333 0.08333331 0.3958333 0.08333331 0.4166666 0.08333331 0.4166666 0.1666666 0.4166666 0.1666666 0.4166666 0.25 0.3958333 0.25 0.4166666 0.25 0.4166666 0.3333333 0.3958333 0.3333333 0.3958333 0.3333333 0.4166666 0.3333333 0.4166666 0.4166666 0.4166666 0.4166666 0.4166666 0.5 0.3958333 0.5 0.4166666 0.5 0.4375 0.5 0.4375 0.5833333 0.4166666 0.5833333 0.4375 0.5833333 0.4375 0.6666667 0.4166666 0.6666667 0.4375 0.6666667 0.4375 0.75 0.4166666 0.75 0.4375 0.75 0.4375 0.8333333 0.4375 0.8333333 0.4375 0.9166667 0.4166666 0.9166667 0.4166666 0.9166667 0.4375 0.9166667 0.4375 1 0.4375 0 0.4375 0.08333331 0.4166666 0.08333331 0.4375 0.08333331 0.4375 0.1666666 0.4166666 0.1666666 0.4375 0.1666666 0.4375 0.25 0.4166666 0.25 0.4375 0.25 0.4375 0.3333333 0.4166666 0.3333333 0.4375 0.3333333 0.4375 0.4166666 0.4166666 0.4166666 0.4375 0.4166666 0.4375 0.5 0.4166666 0.5 0.4583333 0.5 0.4583333 0.5833333 0.4375 0.5833333 0.4583333 0.5833333 0.4583333 0.6666667 0.4375 0.6666667 0.4583333 0.6666667 0.4583333 0.75 0.4375 0.75 0.4583333 0.75 0.4583333 0.8333333 0.4375 0.8333333 0.4583333 0.8333333 0.4583333 0.9166667 0.4375 0.9166667 0.4583333 0.9166667 0.4583333 1 0.4375 1 0.4375 0 0.4583333 0 0.4583333 0.08333331 0.4375 0.08333331 0.4583333 0.08333331 0.4583333 0.1666666 0.4583333 0.1666666 0.4583333 0.25 0.4375 0.25 0.4375 0.25 0.4583333 0.25 0.4583333 0.3333333 0.4583333 0.3333333 0.4583333 0.4166666 0.4375 0.4166666 0.4375 0.4166666 0.4583333 0.4166666 0.4583333 0.5 0.4791666 0.5 0.4791666 0.5833333 0.4583333 0.5833333 0.4583333 0.5833333 0.4791666 0.5833333 0.4791666 0.6666667 0.4583333 0.6666667 0.4791666 0.6666667 0.4791666 0.75 0.4583333 0.75 0.4791666 0.75 0.4791666 0.8333333 0.4583333 0.8333333 0.4791666 0.8333333 0.4791666 0.9166667 0.4583333 0.9166667 0.4791666 0.9166667 0.4791666 1 0.4791666 0 0.4791666 0.08333331 0.4583333 0.08333331 0.4791666 0.08333331 0.4791666 0.1666666 0.4583333 0.1666666 0.4791666 0.1666666 0.4791666 0.25 0.4583333 0.25 0.4791666 0.25 0.4791666 0.3333333 0.4583333 0.3333333 0.4791666 0.3333333 0.4791666 0.4166666 0.4583333 0.4166666 0.4791666 0.4166666 0.4791666 0.5 0.4583333 0.5 0.5 0.5 0.5 0.5833333 0.4791666 0.5833333 0.5 0.5833333 0.5 0.6666667 0.4791666 0.6666667 0.5 0.6666667 0.5 0.75 0.4791666 0.75 0.5 0.75 0.5 0.8333333 0.4791666 0.8333333 0.4791666 0.8333333 0.5 0.8333333 0.5 0.9166667 0.5 0.9166667 0.5 1 0.4791666 1 0.4791666 0 0.5 0 0.5 0.08333331 0.5 0.08333331 0.5 0.1666666 0.4791666 0.1666666 0.4791666 0.1666666 0.5 0.1666666 0.5 0.25 0.4791666 0.25 0.5 0.25 0.5 0.3333333 0.4791666 0.3333333 0.5 0.3333333 0.5 0.4166666 0.4791666 0.4166666 0.5 0.4166666 0.5 0.5 + + + + + + + + + + + + + + +

0 0 0 13 0 1 1 0 2 1 1 3 14 1 4 2 1 5 2 2 6 15 2 7 3 2 8 3 3 9 16 3 10 4 3 11 16 4 12 5 4 13 4 4 14 5 5 15 18 5 16 6 5 17 18 6 18 7 6 19 6 6 20 7 7 21 20 7 22 8 7 23 20 8 24 9 8 25 8 8 26 21 9 27 10 9 28 9 9 29 22 10 30 11 10 31 10 10 32 23 11 33 0 11 34 11 11 35 24 12 36 13 12 37 12 12 38 25 13 39 14 13 40 13 13 41 26 14 42 15 14 43 14 14 44 27 15 45 16 15 46 15 15 47 28 16 48 17 16 49 16 16 50 17 17 51 30 17 52 18 17 53 30 18 54 19 18 55 18 18 56 19 19 57 32 19 58 20 19 59 20 20 60 33 20 61 21 20 62 21 21 63 34 21 64 22 21 65 22 22 66 35 22 67 23 22 68 23 23 69 24 23 70 12 23 71 24 24 72 37 24 73 25 24 74 37 25 75 26 25 76 25 25 77 38 26 78 27 26 79 26 26 80 27 27 81 40 27 82 28 27 83 28 28 84 41 28 85 29 28 86 29 29 87 42 29 88 30 29 89 42 30 90 31 30 91 30 30 92 43 31 93 32 31 94 31 31 95 44 32 96 33 32 97 32 32 98 33 33 99 46 33 100 34 33 101 46 34 102 35 34 103 34 34 104 47 35 105 24 35 106 35 35 107 36 36 108 49 36 109 37 36 110 49 37 111 38 37 112 37 37 113 38 38 114 51 38 115 39 38 116 51 39 117 40 39 118 39 39 119 52 40 120 41 40 121 40 40 122 53 41 123 42 41 124 41 41 125 42 42 126 55 42 127 43 42 128 55 43 129 44 43 130 43 43 131 44 44 132 57 44 133 45 44 134 57 45 135 46 45 136 45 45 137 46 46 138 59 46 139 47 46 140 59 47 141 36 47 142 47 47 143 60 48 144 49 48 145 48 48 146 49 49 147 62 49 148 50 49 149 62 50 150 51 50 151 50 50 152 63 51 153 52 51 154 51 51 155 52 52 156 65 52 157 53 52 158 65 53 159 54 53 160 53 53 161 54 54 162 67 54 163 55 54 164 67 55 165 56 55 166 55 55 167 56 56 168 69 56 169 57 56 170 69 57 171 58 57 172 57 57 173 70 58 174 59 58 175 58 58 176 59 59 177 60 59 178 48 59 179 72 60 180 61 60 181 60 60 182 73 61 183 62 61 184 61 61 185 74 62 186 63 62 187 62 62 188 75 63 189 64 63 190 63 63 191 64 64 192 77 64 193 65 64 194 77 65 195 66 65 196 65 65 197 78 66 198 67 66 199 66 66 200 79 67 201 68 67 202 67 67 203 68 68 204 81 68 205 69 68 206 69 69 207 82 69 208 70 69 209 70 70 210 83 70 211 71 70 212 71 71 213 72 71 214 60 71 215 72 72 216 85 72 217 73 72 218 73 73 219 86 73 220 74 73 221 86 74 222 75 74 223 74 74 224 87 75 225 76 75 226 75 75 227 88 76 228 77 76 229 76 76 230 89 77 231 78 77 232 77 77 233 78 78 234 91 78 235 79 78 236 79 79 237 92 79 238 80 79 239 80 80 240 93 80 241 81 80 242 81 81 243 94 81 244 82 81 245 94 82 246 83 82 247 82 82 248 95 83 249 72 83 250 83 83 251 84 84 252 97 84 253 85 84 254 85 85 255 98 85 256 86 85 257 86 86 258 99 86 259 87 86 260 87 87 261 100 87 262 88 87 263 88 88 264 101 88 265 89 88 266 89 89 267 102 89 268 90 89 269 102 90 270 91 90 271 90 90 272 103 91 273 92 91 274 91 91 275 104 92 276 93 92 277 92 92 278 105 93 279 94 93 280 93 93 281 106 94 282 95 94 283 94 94 284 107 95 285 84 95 286 95 95 287 108 96 288 97 96 289 96 96 290 109 97 291 98 97 292 97 97 293 110 98 294 99 98 295 98 98 296 111 99 297 100 99 298 99 99 299 112 100 300 101 100 301 100 100 302 113 101 303 102 101 304 101 101 305 102 102 306 115 102 307 103 102 308 103 103 309 116 103 310 104 103 311 104 104 312 117 104 313 105 104 314 105 105 315 118 105 316 106 105 317 106 106 318 119 106 319 107 106 320 119 107 321 96 107 322 107 107 323 120 108 324 109 108 325 108 108 326 109 109 327 122 109 328 110 109 329 110 110 330 123 110 331 111 110 332 123 111 333 112 111 334 111 111 335 112 112 336 125 112 337 113 112 338 125 113 339 114 113 340 113 113 341 114 114 342 127 114 343 115 114 344 127 115 345 116 115 346 115 115 347 128 116 348 117 116 349 116 116 350 129 117 351 118 117 352 117 117 353 130 118 354 119 118 355 118 118 356 119 119 357 120 119 358 108 119 359 132 120 360 121 120 361 120 120 362 121 121 363 134 121 364 122 121 365 134 122 366 123 122 367 122 122 368 135 123 369 124 123 370 123 123 371 136 124 372 125 124 373 124 124 374 137 125 375 126 125 376 125 125 377 126 126 378 139 126 379 127 126 380 127 127 381 140 127 382 128 127 383 128 128 384 141 128 385 129 128 386 141 129 387 130 129 388 129 129 389 142 130 390 131 130 391 130 130 392 131 131 393 132 131 394 120 131 395 144 132 396 133 132 397 132 132 398 145 133 399 134 133 400 133 133 401 146 134 402 135 134 403 134 134 404 135 135 405 148 135 406 136 135 407 136 136 408 149 136 409 137 136 410 149 137 411 138 137 412 137 137 413 150 138 414 139 138 415 138 138 416 151 139 417 140 139 418 139 139 419 152 140 420 141 140 421 140 140 422 141 141 423 154 141 424 142 141 425 154 142 426 143 142 427 142 142 428 155 143 429 132 143 430 143 143 431 156 144 432 145 144 433 144 144 434 157 145 435 146 145 436 145 145 437 158 146 438 147 146 439 146 146 440 159 147 441 148 147 442 147 147 443 148 148 444 161 148 445 149 148 446 161 149 447 150 149 448 149 149 449 162 150 450 151 150 451 150 150 452 163 151 453 152 151 454 151 151 455 152 152 456 165 152 457 153 152 458 153 153 459 166 153 460 154 153 461 154 154 462 167 154 463 155 154 464 155 155 465 156 155 466 144 155 467 156 156 468 169 156 469 157 156 470 157 157 471 170 157 472 158 157 473 158 158 474 171 158 475 159 158 476 159 159 477 172 159 478 160 159 479 160 160 480 173 160 481 161 160 482 173 161 483 162 161 484 161 161 485 162 162 486 175 162 487 163 162 488 175 163 489 164 163 490 163 163 491 176 164 492 165 164 493 164 164 494 177 165 495 166 165 496 165 165 497 178 166 498 167 166 499 166 166 500 179 167 501 156 167 502 167 167 503 180 168 504 169 168 505 168 168 506 181 169 507 170 169 508 169 169 509 170 170 510 183 170 511 171 170 512 183 171 513 172 171 514 171 171 515 184 172 516 173 172 517 172 172 518 185 173 519 174 173 520 173 173 521 174 174 522 187 174 523 175 174 524 175 175 525 188 175 526 176 175 527 176 176 528 189 176 529 177 176 530 189 177 531 178 177 532 177 177 533 178 178 534 191 178 535 179 178 536 191 179 537 168 179 538 179 179 539 192 180 540 181 180 541 180 180 542 193 181 543 182 181 544 181 181 545 194 182 546 183 182 547 182 182 548 183 183 549 196 183 550 184 183 551 184 184 552 197 184 553 185 184 554 185 185 555 198 185 556 186 185 557 198 186 558 187 186 559 186 186 560 199 187 561 188 187 562 187 187 563 200 188 564 189 188 565 188 188 566 189 189 567 202 189 568 190 189 569 202 190 570 191 190 571 190 190 572 203 191 573 180 191 574 191 191 575 204 192 576 193 192 577 192 192 578 205 193 579 194 193 580 193 193 581 206 194 582 195 194 583 194 194 584 207 195 585 196 195 586 195 195 587 208 196 588 197 196 589 196 196 590 197 197 591 210 197 592 198 197 593 210 198 594 199 198 595 198 198 596 199 199 597 212 199 598 200 199 599 200 200 600 213 200 601 201 200 602 201 201 603 214 201 604 202 201 605 202 202 606 215 202 607 203 202 608 203 203 609 204 203 610 192 203 611 204 204 612 217 204 613 205 204 614 217 205 615 206 205 616 205 205 617 206 206 618 219 206 619 207 206 620 219 207 621 208 207 622 207 207 623 220 208 624 209 208 625 208 208 626 209 209 627 222 209 628 210 209 629 222 210 630 211 210 631 210 210 632 211 211 633 224 211 634 212 211 635 212 212 636 225 212 637 213 212 638 225 213 639 214 213 640 213 213 641 226 214 642 215 214 643 214 214 644 227 215 645 204 215 646 215 215 647 216 216 648 229 216 649 217 216 650 229 217 651 218 217 652 217 217 653 230 218 654 219 218 655 218 218 656 219 219 657 232 219 658 220 219 659 220 220 660 233 220 661 221 220 662 221 221 663 234 221 664 222 221 665 234 222 666 223 222 667 222 222 668 235 223 669 224 223 670 223 223 671 236 224 672 225 224 673 224 224 674 225 225 675 238 225 676 226 225 677 226 226 678 239 226 679 227 226 680 239 227 681 216 227 682 227 227 683 228 228 684 241 228 685 229 228 686 241 229 687 230 229 688 229 229 689 230 230 690 243 230 691 231 230 692 243 231 693 232 231 694 231 231 695 244 232 696 233 232 697 232 232 698 245 233 699 234 233 700 233 233 701 234 234 702 247 234 703 235 234 704 235 235 705 248 235 706 236 235 707 248 236 708 237 236 709 236 236 710 249 237 711 238 237 712 237 237 713 238 238 714 251 238 715 239 238 716 251 239 717 228 239 718 239 239 719 240 240 720 253 240 721 241 240 722 253 241 723 242 241 724 241 241 725 242 242 726 255 242 727 243 242 728 243 243 729 256 243 730 244 243 731 256 244 732 245 244 733 244 244 734 257 245 735 246 245 736 245 245 737 246 246 738 259 246 739 247 246 740 259 247 741 248 247 742 247 247 743 260 248 744 249 248 745 248 248 746 261 249 747 250 249 748 249 249 749 250 250 750 263 250 751 251 250 752 263 251 753 240 251 754 251 251 755 264 252 756 253 252 757 252 252 758 253 253 759 266 253 760 254 253 761 266 254 762 255 254 763 254 254 764 255 255 765 268 255 766 256 255 767 256 256 768 269 256 769 257 256 770 257 257 771 270 257 772 258 257 773 270 258 774 259 258 775 258 258 776 271 259 777 260 259 778 259 259 779 272 260 780 261 260 781 260 260 782 273 261 783 262 261 784 261 261 785 274 262 786 263 262 787 262 262 788 275 263 789 252 263 790 263 263 791 276 264 792 265 264 793 264 264 794 277 265 795 266 265 796 265 265 797 278 266 798 267 266 799 266 266 800 279 267 801 268 267 802 267 267 803 280 268 804 269 268 805 268 268 806 269 269 807 282 269 808 270 269 809 282 270 810 271 270 811 270 270 812 271 271 813 284 271 814 272 271 815 272 272 816 285 272 817 273 272 818 273 273 819 286 273 820 274 273 821 274 274 822 287 274 823 275 274 824 275 275 825 276 275 826 264 275 827 276 276 828 289 276 829 277 276 830 277 277 831 290 277 832 278 277 833 278 278 834 291 278 835 279 278 836 291 279 837 280 279 838 279 279 839 292 280 840 281 280 841 280 280 842 293 281 843 282 281 844 281 281 845 294 282 846 283 282 847 282 282 848 283 283 849 296 283 850 284 283 851 296 284 852 285 284 853 284 284 854 297 285 855 286 285 856 285 285 857 298 286 858 287 286 859 286 286 860 299 287 861 276 287 862 287 287 863 300 288 864 289 288 865 288 288 866 301 289 867 290 289 868 289 289 869 302 290 870 291 290 871 290 290 872 303 291 873 292 291 874 291 291 875 292 292 876 305 292 877 293 292 878 305 293 879 294 293 880 293 293 881 306 294 882 295 294 883 294 294 884 307 295 885 296 295 886 295 295 887 296 296 888 309 296 889 297 296 890 297 297 891 310 297 892 298 297 893 298 298 894 311 298 895 299 298 896 299 299 897 300 299 898 288 299 899 300 300 900 313 300 901 301 300 902 301 301 903 314 301 904 302 301 905 302 302 906 315 302 907 303 302 908 303 303 909 316 303 910 304 303 911 304 304 912 317 304 913 305 304 914 317 305 915 306 305 916 305 305 917 306 306 918 319 306 919 307 306 920 319 307 921 308 307 922 307 307 923 320 308 924 309 308 925 308 308 926 321 309 927 310 309 928 309 309 929 322 310 930 311 310 931 310 310 932 323 311 933 300 311 934 311 311 935 324 312 936 313 312 937 312 312 938 325 313 939 314 313 940 313 313 941 314 314 942 327 314 943 315 314 944 327 315 945 316 315 946 315 315 947 328 316 948 317 316 949 316 316 950 329 317 951 318 317 952 317 317 953 318 318 954 331 318 955 319 318 956 319 319 957 332 319 958 320 319 959 320 320 960 333 320 961 321 320 962 333 321 963 322 321 964 321 321 965 322 322 966 335 322 967 323 322 968 335 323 969 312 323 970 323 323 971 336 324 972 325 324 973 324 324 974 337 325 975 326 325 976 325 325 977 338 326 978 327 326 979 326 326 980 339 327 981 328 327 982 327 327 983 340 328 984 329 328 985 328 328 986 329 329 987 342 329 988 330 329 989 342 330 990 331 330 991 330 330 992 331 331 993 344 331 994 332 331 995 344 332 996 333 332 997 332 332 998 333 333 999 346 333 1000 334 333 1001 334 334 1002 347 334 1003 335 334 1004 335 335 1005 336 335 1006 324 335 1007 348 336 1008 337 336 1009 336 336 1010 349 337 1011 338 337 1012 337 337 1013 350 338 1014 339 338 1015 338 338 1016 351 339 1017 340 339 1018 339 339 1019 340 340 1020 353 340 1021 341 340 1022 341 341 1023 354 341 1024 342 341 1025 354 342 1026 343 342 1027 342 342 1028 355 343 1029 344 343 1030 343 343 1031 356 344 1032 345 344 1033 344 344 1034 345 345 1035 358 345 1036 346 345 1037 346 346 1038 359 346 1039 347 346 1040 347 347 1041 348 347 1042 336 347 1043 360 348 1044 349 348 1045 348 348 1046 349 349 1047 362 349 1048 350 349 1049 350 350 1050 363 350 1051 351 350 1052 363 351 1053 352 351 1054 351 351 1055 364 352 1056 353 352 1057 352 352 1058 365 353 1059 354 353 1060 353 353 1061 354 354 1062 367 354 1063 355 354 1064 355 355 1065 368 355 1066 356 355 1067 356 356 1068 369 356 1069 357 356 1070 369 357 1071 358 357 1072 357 357 1073 370 358 1074 359 358 1075 358 358 1076 359 359 1077 360 359 1078 348 359 1079 372 360 1080 361 360 1081 360 360 1082 361 361 1083 374 361 1084 362 361 1085 362 362 1086 375 362 1087 363 362 1088 363 363 1089 376 363 1090 364 363 1091 364 364 1092 377 364 1093 365 364 1094 377 365 1095 366 365 1096 365 365 1097 378 366 1098 367 366 1099 366 366 1100 379 367 1101 368 367 1102 367 367 1103 380 368 1104 369 368 1105 368 368 1106 381 369 1107 370 369 1108 369 369 1109 382 370 1110 371 370 1111 370 370 1112 383 371 1113 360 371 1114 371 371 1115 372 372 1116 385 372 1117 373 372 1118 385 373 1119 374 373 1120 373 373 1121 374 374 1122 387 374 1123 375 374 1124 375 375 1125 388 375 1126 376 375 1127 376 376 1128 389 376 1129 377 376 1130 389 377 1131 378 377 1132 377 377 1133 378 378 1134 391 378 1135 379 378 1136 391 379 1137 380 379 1138 379 379 1139 392 380 1140 381 380 1141 380 380 1142 393 381 1143 382 381 1144 381 381 1145 394 382 1146 383 382 1147 382 382 1148 395 383 1149 372 383 1150 383 383 1151 396 384 1152 385 384 1153 384 384 1154 397 385 1155 386 385 1156 385 385 1157 386 386 1158 399 386 1159 387 386 1160 399 387 1161 388 387 1162 387 387 1163 400 388 1164 389 388 1165 388 388 1166 401 389 1167 390 389 1168 389 389 1169 390 390 1170 403 390 1171 391 390 1172 391 391 1173 404 391 1174 392 391 1175 392 392 1176 405 392 1177 393 392 1178 405 393 1179 394 393 1180 393 393 1181 406 394 1182 395 394 1183 394 394 1184 407 395 1185 384 395 1186 395 395 1187 396 396 1188 409 396 1189 397 396 1190 409 397 1191 398 397 1192 397 397 1193 410 398 1194 399 398 1195 398 398 1196 399 399 1197 412 399 1198 400 399 1199 400 400 1200 413 400 1201 401 400 1202 413 401 1203 402 401 1204 401 401 1205 414 402 1206 403 402 1207 402 402 1208 415 403 1209 404 403 1210 403 403 1211 416 404 1212 405 404 1213 404 404 1214 405 405 1215 418 405 1216 406 405 1217 406 406 1218 419 406 1219 407 406 1220 419 407 1221 396 407 1222 407 407 1223 408 408 1224 421 408 1225 409 408 1226 421 409 1227 410 409 1228 409 409 1229 422 410 1230 411 410 1231 410 410 1232 423 411 1233 412 411 1234 411 411 1235 412 412 1236 425 412 1237 413 412 1238 425 413 1239 414 413 1240 413 413 1241 414 414 1242 427 414 1243 415 414 1244 427 415 1245 416 415 1246 415 415 1247 416 416 1248 429 416 1249 417 416 1250 429 417 1251 418 417 1252 417 417 1253 430 418 1254 419 418 1255 418 418 1256 431 419 1257 408 419 1258 419 419 1259 432 420 1260 421 420 1261 420 420 1262 433 421 1263 422 421 1264 421 421 1265 434 422 1266 423 422 1267 422 422 1268 423 423 1269 436 423 1270 424 423 1271 436 424 1272 425 424 1273 424 424 1274 425 425 1275 438 425 1276 426 425 1277 438 426 1278 427 426 1279 426 426 1280 439 427 1281 428 427 1282 427 427 1283 440 428 1284 429 428 1285 428 428 1286 441 429 1287 430 429 1288 429 429 1289 430 430 1290 443 430 1291 431 430 1292 443 431 1293 420 431 1294 431 431 1295 444 432 1296 433 432 1297 432 432 1298 445 433 1299 434 433 1300 433 433 1301 434 434 1302 447 434 1303 435 434 1304 447 435 1305 436 435 1306 435 435 1307 448 436 1308 437 436 1309 436 436 1310 449 437 1311 438 437 1312 437 437 1313 450 438 1314 439 438 1315 438 438 1316 439 439 1317 452 439 1318 440 439 1319 440 440 1320 453 440 1321 441 440 1322 453 441 1323 442 441 1324 441 441 1325 454 442 1326 443 442 1327 442 442 1328 455 443 1329 432 443 1330 443 443 1331 456 444 1332 445 444 1333 444 444 1334 457 445 1335 446 445 1336 445 445 1337 458 446 1338 447 446 1339 446 446 1340 459 447 1341 448 447 1342 447 447 1343 448 448 1344 461 448 1345 449 448 1346 461 449 1347 450 449 1348 449 449 1349 462 450 1350 451 450 1351 450 450 1352 463 451 1353 452 451 1354 451 451 1355 452 452 1356 465 452 1357 453 452 1358 453 453 1359 466 453 1360 454 453 1361 454 454 1362 467 454 1363 455 454 1364 467 455 1365 444 455 1366 455 455 1367 468 456 1368 457 456 1369 456 456 1370 469 457 1371 458 457 1372 457 457 1373 470 458 1374 459 458 1375 458 458 1376 459 459 1377 472 459 1378 460 459 1379 472 460 1380 461 460 1381 460 460 1382 461 461 1383 474 461 1384 462 461 1385 474 462 1386 463 462 1387 462 462 1388 475 463 1389 464 463 1390 463 463 1391 476 464 1392 465 464 1393 464 464 1394 477 465 1395 466 465 1396 465 465 1397 466 466 1398 479 466 1399 467 466 1400 467 467 1401 468 467 1402 456 467 1403 480 468 1404 469 468 1405 468 468 1406 469 469 1407 482 469 1408 470 469 1409 470 470 1410 483 470 1411 471 470 1412 471 471 1413 484 471 1414 472 471 1415 472 472 1416 485 472 1417 473 472 1418 473 473 1419 486 473 1420 474 473 1421 486 474 1422 475 474 1423 474 474 1424 487 475 1425 476 475 1426 475 475 1427 488 476 1428 477 476 1429 476 476 1430 489 477 1431 478 477 1432 477 477 1433 490 478 1434 479 478 1435 478 478 1436 491 479 1437 468 479 1438 479 479 1439 480 480 1440 493 480 1441 481 480 1442 493 481 1443 482 481 1444 481 481 1445 494 482 1446 483 482 1447 482 482 1448 495 483 1449 484 483 1450 483 483 1451 496 484 1452 485 484 1453 484 484 1454 497 485 1455 486 485 1456 485 485 1457 486 486 1458 499 486 1459 487 486 1460 487 487 1461 500 487 1462 488 487 1463 488 488 1464 501 488 1465 489 488 1466 489 489 1467 502 489 1468 490 489 1469 490 490 1470 503 490 1471 491 490 1472 503 491 1473 480 491 1474 491 491 1475 492 492 1476 505 492 1477 493 492 1478 505 493 1479 494 493 1480 493 493 1481 494 494 1482 507 494 1483 495 494 1484 495 495 1485 508 495 1486 496 495 1487 496 496 1488 509 496 1489 497 496 1490 497 497 1491 510 497 1492 498 497 1493 510 498 1494 499 498 1495 498 498 1496 511 499 1497 500 499 1498 499 499 1499 512 500 1500 501 500 1501 500 500 1502 513 501 1503 502 501 1504 501 501 1505 514 502 1506 503 502 1507 502 502 1508 515 503 1509 492 503 1510 503 503 1511 504 504 1512 517 504 1513 505 504 1514 517 505 1515 506 505 1516 505 505 1517 506 506 1518 519 506 1519 507 506 1520 519 507 1521 508 507 1522 507 507 1523 520 508 1524 509 508 1525 508 508 1526 509 509 1527 522 509 1528 510 509 1529 522 510 1530 511 510 1531 510 510 1532 511 511 1533 524 511 1534 512 511 1535 524 512 1536 513 512 1537 512 512 1538 525 513 1539 514 513 1540 513 513 1541 514 514 1542 527 514 1543 515 514 1544 527 515 1545 504 515 1546 515 515 1547 516 516 1548 529 516 1549 517 516 1550 529 517 1551 518 517 1552 517 517 1553 530 518 1554 519 518 1555 518 518 1556 519 519 1557 532 519 1558 520 519 1559 532 520 1560 521 520 1561 520 520 1562 521 521 1563 534 521 1564 522 521 1565 534 522 1566 523 522 1567 522 522 1568 523 523 1569 536 523 1570 524 523 1571 536 524 1572 525 524 1573 524 524 1574 537 525 1575 526 525 1576 525 525 1577 526 526 1578 539 526 1579 527 526 1580 539 527 1581 516 527 1582 527 527 1583 528 528 1584 541 528 1585 529 528 1586 529 529 1587 542 529 1588 530 529 1589 530 530 1590 543 530 1591 531 530 1592 531 531 1593 544 531 1594 532 531 1595 544 532 1596 533 532 1597 532 532 1598 533 533 1599 546 533 1600 534 533 1601 546 534 1602 535 534 1603 534 534 1604 547 535 1605 536 535 1606 535 535 1607 548 536 1608 537 536 1609 536 536 1610 549 537 1611 538 537 1612 537 537 1613 550 538 1614 539 538 1615 538 538 1616 551 539 1617 528 539 1618 539 539 1619 552 540 1620 541 540 1621 540 540 1622 553 541 1623 542 541 1624 541 541 1625 554 542 1626 543 542 1627 542 542 1628 555 543 1629 544 543 1630 543 543 1631 556 544 1632 545 544 1633 544 544 1634 557 545 1635 546 545 1636 545 545 1637 546 546 1638 559 546 1639 547 546 1640 547 547 1641 560 547 1642 548 547 1643 560 548 1644 549 548 1645 548 548 1646 549 549 1647 562 549 1648 550 549 1649 562 550 1650 551 550 1651 550 550 1652 551 551 1653 552 551 1654 540 551 1655 564 552 1656 553 552 1657 552 552 1658 553 553 1659 566 553 1660 554 553 1661 554 554 1662 567 554 1663 555 554 1664 555 555 1665 568 555 1666 556 555 1667 556 556 1668 569 556 1669 557 556 1670 557 557 1671 570 557 1672 558 557 1673 570 558 1674 559 558 1675 558 558 1676 571 559 1677 560 559 1678 559 559 1679 572 560 1680 561 560 1681 560 560 1682 573 561 1683 562 561 1684 561 561 1685 574 562 1686 563 562 1687 562 562 1688 575 563 1689 552 563 1690 563 563 1691 0 564 1692 565 564 1693 564 564 1694 1 565 1695 566 565 1696 565 565 1697 2 566 1698 567 566 1699 566 566 1700 3 567 1701 568 567 1702 567 567 1703 568 568 1704 5 568 1705 569 568 1706 5 569 1707 570 569 1708 569 569 1709 570 570 1710 7 570 1711 571 570 1712 7 571 1713 572 571 1714 571 571 1715 572 572 1716 9 572 1717 573 572 1718 573 573 1719 10 573 1720 574 573 1721 574 574 1722 11 574 1723 575 574 1724 575 575 1725 0 575 1726 564 575 1727 0 576 1728 12 576 1729 13 576 1730 1 577 1731 13 577 1732 14 577 1733 2 578 1734 14 578 1735 15 578 1736 3 579 1737 15 579 1738 16 579 1739 16 580 1740 17 580 1741 5 580 1742 5 581 1743 17 581 1744 18 581 1745 18 582 1746 19 582 1747 7 582 1748 7 583 1749 19 583 1750 20 583 1751 20 584 1752 21 584 1753 9 584 1754 21 585 1755 22 585 1756 10 585 1757 22 586 1758 23 586 1759 11 586 1760 23 587 1761 12 587 1762 0 587 1763 24 588 1764 25 588 1765 13 588 1766 25 589 1767 26 589 1768 14 589 1769 26 590 1770 27 590 1771 15 590 1772 27 591 1773 28 591 1774 16 591 1775 28 592 1776 29 592 1777 17 592 1778 17 593 1779 29 593 1780 30 593 1781 30 594 1782 31 594 1783 19 594 1784 19 595 1785 31 595 1786 32 595 1787 20 596 1788 32 596 1789 33 596 1790 21 597 1791 33 597 1792 34 597 1793 22 598 1794 34 598 1795 35 598 1796 23 599 1797 35 599 1798 24 599 1799 24 600 1800 36 600 1801 37 600 1802 37 601 1803 38 601 1804 26 601 1805 38 602 1806 39 602 1807 27 602 1808 27 603 1809 39 603 1810 40 603 1811 28 604 1812 40 604 1813 41 604 1814 29 605 1815 41 605 1816 42 605 1817 42 606 1818 43 606 1819 31 606 1820 43 607 1821 44 607 1822 32 607 1823 44 608 1824 45 608 1825 33 608 1826 33 609 1827 45 609 1828 46 609 1829 46 610 1830 47 610 1831 35 610 1832 47 611 1833 36 611 1834 24 611 1835 36 612 1836 48 612 1837 49 612 1838 49 613 1839 50 613 1840 38 613 1841 38 614 1842 50 614 1843 51 614 1844 51 615 1845 52 615 1846 40 615 1847 52 616 1848 53 616 1849 41 616 1850 53 617 1851 54 617 1852 42 617 1853 42 618 1854 54 618 1855 55 618 1856 55 619 1857 56 619 1858 44 619 1859 44 620 1860 56 620 1861 57 620 1862 57 621 1863 58 621 1864 46 621 1865 46 622 1866 58 622 1867 59 622 1868 59 623 1869 48 623 1870 36 623 1871 60 624 1872 61 624 1873 49 624 1874 49 625 1875 61 625 1876 62 625 1877 62 626 1878 63 626 1879 51 626 1880 63 627 1881 64 627 1882 52 627 1883 52 628 1884 64 628 1885 65 628 1886 65 629 1887 66 629 1888 54 629 1889 54 630 1890 66 630 1891 67 630 1892 67 631 1893 68 631 1894 56 631 1895 56 632 1896 68 632 1897 69 632 1898 69 633 1899 70 633 1900 58 633 1901 70 634 1902 71 634 1903 59 634 1904 59 635 1905 71 635 1906 60 635 1907 72 636 1908 73 636 1909 61 636 1910 73 637 1911 74 637 1912 62 637 1913 74 638 1914 75 638 1915 63 638 1916 75 639 1917 76 639 1918 64 639 1919 64 640 1920 76 640 1921 77 640 1922 77 641 1923 78 641 1924 66 641 1925 78 642 1926 79 642 1927 67 642 1928 79 643 1929 80 643 1930 68 643 1931 68 644 1932 80 644 1933 81 644 1934 69 645 1935 81 645 1936 82 645 1937 70 646 1938 82 646 1939 83 646 1940 71 647 1941 83 647 1942 72 647 1943 72 648 1944 84 648 1945 85 648 1946 73 649 1947 85 649 1948 86 649 1949 86 650 1950 87 650 1951 75 650 1952 87 651 1953 88 651 1954 76 651 1955 88 652 1956 89 652 1957 77 652 1958 89 653 1959 90 653 1960 78 653 1961 78 654 1962 90 654 1963 91 654 1964 79 655 1965 91 655 1966 92 655 1967 80 656 1968 92 656 1969 93 656 1970 81 657 1971 93 657 1972 94 657 1973 94 658 1974 95 658 1975 83 658 1976 95 659 1977 84 659 1978 72 659 1979 84 660 1980 96 660 1981 97 660 1982 85 661 1983 97 661 1984 98 661 1985 86 662 1986 98 662 1987 99 662 1988 87 663 1989 99 663 1990 100 663 1991 88 664 1992 100 664 1993 101 664 1994 89 665 1995 101 665 1996 102 665 1997 102 666 1998 103 666 1999 91 666 2000 103 667 2001 104 667 2002 92 667 2003 104 668 2004 105 668 2005 93 668 2006 105 669 2007 106 669 2008 94 669 2009 106 670 2010 107 670 2011 95 670 2012 107 671 2013 96 671 2014 84 671 2015 108 672 2016 109 672 2017 97 672 2018 109 673 2019 110 673 2020 98 673 2021 110 674 2022 111 674 2023 99 674 2024 111 675 2025 112 675 2026 100 675 2027 112 676 2028 113 676 2029 101 676 2030 113 677 2031 114 677 2032 102 677 2033 102 678 2034 114 678 2035 115 678 2036 103 679 2037 115 679 2038 116 679 2039 104 680 2040 116 680 2041 117 680 2042 105 681 2043 117 681 2044 118 681 2045 106 682 2046 118 682 2047 119 682 2048 119 683 2049 108 683 2050 96 683 2051 120 684 2052 121 684 2053 109 684 2054 109 685 2055 121 685 2056 122 685 2057 110 686 2058 122 686 2059 123 686 2060 123 687 2061 124 687 2062 112 687 2063 112 688 2064 124 688 2065 125 688 2066 125 689 2067 126 689 2068 114 689 2069 114 690 2070 126 690 2071 127 690 2072 127 691 2073 128 691 2074 116 691 2075 128 692 2076 129 692 2077 117 692 2078 129 693 2079 130 693 2080 118 693 2081 130 694 2082 131 694 2083 119 694 2084 119 695 2085 131 695 2086 120 695 2087 132 696 2088 133 696 2089 121 696 2090 121 697 2091 133 697 2092 134 697 2093 134 698 2094 135 698 2095 123 698 2096 135 699 2097 136 699 2098 124 699 2099 136 700 2100 137 700 2101 125 700 2102 137 701 2103 138 701 2104 126 701 2105 126 702 2106 138 702 2107 139 702 2108 127 703 2109 139 703 2110 140 703 2111 128 704 2112 140 704 2113 141 704 2114 141 705 2115 142 705 2116 130 705 2117 142 706 2118 143 706 2119 131 706 2120 131 707 2121 143 707 2122 132 707 2123 144 708 2124 145 708 2125 133 708 2126 145 709 2127 146 709 2128 134 709 2129 146 710 2130 147 710 2131 135 710 2132 135 711 2133 147 711 2134 148 711 2135 136 712 2136 148 712 2137 149 712 2138 149 713 2139 150 713 2140 138 713 2141 150 714 2142 151 714 2143 139 714 2144 151 715 2145 152 715 2146 140 715 2147 152 716 2148 153 716 2149 141 716 2150 141 717 2151 153 717 2152 154 717 2153 154 718 2154 155 718 2155 143 718 2156 155 719 2157 144 719 2158 132 719 2159 156 720 2160 157 720 2161 145 720 2162 157 721 2163 158 721 2164 146 721 2165 158 722 2166 159 722 2167 147 722 2168 159 723 2169 160 723 2170 148 723 2171 148 724 2172 160 724 2173 161 724 2174 161 725 2175 162 725 2176 150 725 2177 162 726 2178 163 726 2179 151 726 2180 163 727 2181 164 727 2182 152 727 2183 152 728 2184 164 728 2185 165 728 2186 153 729 2187 165 729 2188 166 729 2189 154 730 2190 166 730 2191 167 730 2192 155 731 2193 167 731 2194 156 731 2195 156 732 2196 168 732 2197 169 732 2198 157 733 2199 169 733 2200 170 733 2201 158 734 2202 170 734 2203 171 734 2204 159 735 2205 171 735 2206 172 735 2207 160 736 2208 172 736 2209 173 736 2210 173 737 2211 174 737 2212 162 737 2213 162 738 2214 174 738 2215 175 738 2216 175 739 2217 176 739 2218 164 739 2219 176 740 2220 177 740 2221 165 740 2222 177 741 2223 178 741 2224 166 741 2225 178 742 2226 179 742 2227 167 742 2228 179 743 2229 168 743 2230 156 743 2231 180 744 2232 181 744 2233 169 744 2234 181 745 2235 182 745 2236 170 745 2237 170 746 2238 182 746 2239 183 746 2240 183 747 2241 184 747 2242 172 747 2243 184 748 2244 185 748 2245 173 748 2246 185 749 2247 186 749 2248 174 749 2249 174 750 2250 186 750 2251 187 750 2252 175 751 2253 187 751 2254 188 751 2255 176 752 2256 188 752 2257 189 752 2258 189 753 2259 190 753 2260 178 753 2261 178 754 2262 190 754 2263 191 754 2264 191 755 2265 180 755 2266 168 755 2267 192 756 2268 193 756 2269 181 756 2270 193 757 2271 194 757 2272 182 757 2273 194 758 2274 195 758 2275 183 758 2276 183 759 2277 195 759 2278 196 759 2279 184 760 2280 196 760 2281 197 760 2282 185 761 2283 197 761 2284 198 761 2285 198 762 2286 199 762 2287 187 762 2288 199 763 2289 200 763 2290 188 763 2291 200 764 2292 201 764 2293 189 764 2294 189 765 2295 201 765 2296 202 765 2297 202 766 2298 203 766 2299 191 766 2300 203 767 2301 192 767 2302 180 767 2303 204 768 2304 205 768 2305 193 768 2306 205 769 2307 206 769 2308 194 769 2309 206 770 2310 207 770 2311 195 770 2312 207 771 2313 208 771 2314 196 771 2315 208 772 2316 209 772 2317 197 772 2318 197 773 2319 209 773 2320 210 773 2321 210 774 2322 211 774 2323 199 774 2324 199 775 2325 211 775 2326 212 775 2327 200 776 2328 212 776 2329 213 776 2330 201 777 2331 213 777 2332 214 777 2333 202 778 2334 214 778 2335 215 778 2336 203 779 2337 215 779 2338 204 779 2339 204 780 2340 216 780 2341 217 780 2342 217 781 2343 218 781 2344 206 781 2345 206 782 2346 218 782 2347 219 782 2348 219 783 2349 220 783 2350 208 783 2351 220 784 2352 221 784 2353 209 784 2354 209 785 2355 221 785 2356 222 785 2357 222 786 2358 223 786 2359 211 786 2360 211 787 2361 223 787 2362 224 787 2363 212 788 2364 224 788 2365 225 788 2366 225 789 2367 226 789 2368 214 789 2369 226 790 2370 227 790 2371 215 790 2372 227 791 2373 216 791 2374 204 791 2375 216 792 2376 228 792 2377 229 792 2378 229 793 2379 230 793 2380 218 793 2381 230 794 2382 231 794 2383 219 794 2384 219 795 2385 231 795 2386 232 795 2387 220 796 2388 232 796 2389 233 796 2390 221 797 2391 233 797 2392 234 797 2393 234 798 2394 235 798 2395 223 798 2396 235 799 2397 236 799 2398 224 799 2399 236 800 2400 237 800 2401 225 800 2402 225 801 2403 237 801 2404 238 801 2405 226 802 2406 238 802 2407 239 802 2408 239 803 2409 228 803 2410 216 803 2411 228 804 2412 240 804 2413 241 804 2414 241 805 2415 242 805 2416 230 805 2417 230 806 2418 242 806 2419 243 806 2420 243 807 2421 244 807 2422 232 807 2423 244 808 2424 245 808 2425 233 808 2426 245 809 2427 246 809 2428 234 809 2429 234 810 2430 246 810 2431 247 810 2432 235 811 2433 247 811 2434 248 811 2435 248 812 2436 249 812 2437 237 812 2438 249 813 2439 250 813 2440 238 813 2441 238 814 2442 250 814 2443 251 814 2444 251 815 2445 240 815 2446 228 815 2447 240 816 2448 252 816 2449 253 816 2450 253 817 2451 254 817 2452 242 817 2453 242 818 2454 254 818 2455 255 818 2456 243 819 2457 255 819 2458 256 819 2459 256 820 2460 257 820 2461 245 820 2462 257 821 2463 258 821 2464 246 821 2465 246 822 2466 258 822 2467 259 822 2468 259 823 2469 260 823 2470 248 823 2471 260 824 2472 261 824 2473 249 824 2474 261 825 2475 262 825 2476 250 825 2477 250 826 2478 262 826 2479 263 826 2480 263 827 2481 252 827 2482 240 827 2483 264 828 2484 265 828 2485 253 828 2486 253 829 2487 265 829 2488 266 829 2489 266 830 2490 267 830 2491 255 830 2492 255 831 2493 267 831 2494 268 831 2495 256 832 2496 268 832 2497 269 832 2498 257 833 2499 269 833 2500 270 833 2501 270 834 2502 271 834 2503 259 834 2504 271 835 2505 272 835 2506 260 835 2507 272 836 2508 273 836 2509 261 836 2510 273 837 2511 274 837 2512 262 837 2513 274 838 2514 275 838 2515 263 838 2516 275 839 2517 264 839 2518 252 839 2519 276 840 2520 277 840 2521 265 840 2522 277 841 2523 278 841 2524 266 841 2525 278 842 2526 279 842 2527 267 842 2528 279 843 2529 280 843 2530 268 843 2531 280 844 2532 281 844 2533 269 844 2534 269 845 2535 281 845 2536 282 845 2537 282 846 2538 283 846 2539 271 846 2540 271 847 2541 283 847 2542 284 847 2543 272 848 2544 284 848 2545 285 848 2546 273 849 2547 285 849 2548 286 849 2549 274 850 2550 286 850 2551 287 850 2552 275 851 2553 287 851 2554 276 851 2555 276 852 2556 288 852 2557 289 852 2558 277 853 2559 289 853 2560 290 853 2561 278 854 2562 290 854 2563 291 854 2564 291 855 2565 292 855 2566 280 855 2567 292 856 2568 293 856 2569 281 856 2570 293 857 2571 294 857 2572 282 857 2573 294 858 2574 295 858 2575 283 858 2576 283 859 2577 295 859 2578 296 859 2579 296 860 2580 297 860 2581 285 860 2582 297 861 2583 298 861 2584 286 861 2585 298 862 2586 299 862 2587 287 862 2588 299 863 2589 288 863 2590 276 863 2591 300 864 2592 301 864 2593 289 864 2594 301 865 2595 302 865 2596 290 865 2597 302 866 2598 303 866 2599 291 866 2600 303 867 2601 304 867 2602 292 867 2603 292 868 2604 304 868 2605 305 868 2606 305 869 2607 306 869 2608 294 869 2609 306 870 2610 307 870 2611 295 870 2612 307 871 2613 308 871 2614 296 871 2615 296 872 2616 308 872 2617 309 872 2618 297 873 2619 309 873 2620 310 873 2621 298 874 2622 310 874 2623 311 874 2624 299 875 2625 311 875 2626 300 875 2627 300 876 2628 312 876 2629 313 876 2630 301 877 2631 313 877 2632 314 877 2633 302 878 2634 314 878 2635 315 878 2636 303 879 2637 315 879 2638 316 879 2639 304 880 2640 316 880 2641 317 880 2642 317 881 2643 318 881 2644 306 881 2645 306 882 2646 318 882 2647 319 882 2648 319 883 2649 320 883 2650 308 883 2651 320 884 2652 321 884 2653 309 884 2654 321 885 2655 322 885 2656 310 885 2657 322 886 2658 323 886 2659 311 886 2660 323 887 2661 312 887 2662 300 887 2663 324 888 2664 325 888 2665 313 888 2666 325 889 2667 326 889 2668 314 889 2669 314 890 2670 326 890 2671 327 890 2672 327 891 2673 328 891 2674 316 891 2675 328 892 2676 329 892 2677 317 892 2678 329 893 2679 330 893 2680 318 893 2681 318 894 2682 330 894 2683 331 894 2684 319 895 2685 331 895 2686 332 895 2687 320 896 2688 332 896 2689 333 896 2690 333 897 2691 334 897 2692 322 897 2693 322 898 2694 334 898 2695 335 898 2696 335 899 2697 324 899 2698 312 899 2699 336 900 2700 337 900 2701 325 900 2702 337 901 2703 338 901 2704 326 901 2705 338 902 2706 339 902 2707 327 902 2708 339 903 2709 340 903 2710 328 903 2711 340 904 2712 341 904 2713 329 904 2714 329 905 2715 341 905 2716 342 905 2717 342 906 2718 343 906 2719 331 906 2720 331 907 2721 343 907 2722 344 907 2723 344 908 2724 345 908 2725 333 908 2726 333 909 2727 345 909 2728 346 909 2729 334 910 2730 346 910 2731 347 910 2732 335 911 2733 347 911 2734 336 911 2735 348 912 2736 349 912 2737 337 912 2738 349 913 2739 350 913 2740 338 913 2741 350 914 2742 351 914 2743 339 914 2744 351 915 2745 352 915 2746 340 915 2747 340 916 2748 352 916 2749 353 916 2750 341 917 2751 353 917 2752 354 917 2753 354 918 2754 355 918 2755 343 918 2756 355 919 2757 356 919 2758 344 919 2759 356 920 2760 357 920 2761 345 920 2762 345 921 2763 357 921 2764 358 921 2765 346 922 2766 358 922 2767 359 922 2768 347 923 2769 359 923 2770 348 923 2771 360 924 2772 361 924 2773 349 924 2774 349 925 2775 361 925 2776 362 925 2777 350 926 2778 362 926 2779 363 926 2780 363 927 2781 364 927 2782 352 927 2783 364 928 2784 365 928 2785 353 928 2786 365 929 2787 366 929 2788 354 929 2789 354 930 2790 366 930 2791 367 930 2792 355 931 2793 367 931 2794 368 931 2795 356 932 2796 368 932 2797 369 932 2798 369 933 2799 370 933 2800 358 933 2801 370 934 2802 371 934 2803 359 934 2804 359 935 2805 371 935 2806 360 935 2807 372 936 2808 373 936 2809 361 936 2810 361 937 2811 373 937 2812 374 937 2813 362 938 2814 374 938 2815 375 938 2816 363 939 2817 375 939 2818 376 939 2819 364 940 2820 376 940 2821 377 940 2822 377 941 2823 378 941 2824 366 941 2825 378 942 2826 379 942 2827 367 942 2828 379 943 2829 380 943 2830 368 943 2831 380 944 2832 381 944 2833 369 944 2834 381 945 2835 382 945 2836 370 945 2837 382 946 2838 383 946 2839 371 946 2840 383 947 2841 372 947 2842 360 947 2843 372 948 2844 384 948 2845 385 948 2846 385 949 2847 386 949 2848 374 949 2849 374 950 2850 386 950 2851 387 950 2852 375 951 2853 387 951 2854 388 951 2855 376 952 2856 388 952 2857 389 952 2858 389 953 2859 390 953 2860 378 953 2861 378 954 2862 390 954 2863 391 954 2864 391 955 2865 392 955 2866 380 955 2867 392 956 2868 393 956 2869 381 956 2870 393 957 2871 394 957 2872 382 957 2873 394 958 2874 395 958 2875 383 958 2876 395 959 2877 384 959 2878 372 959 2879 396 960 2880 397 960 2881 385 960 2882 397 961 2883 398 961 2884 386 961 2885 386 962 2886 398 962 2887 399 962 2888 399 963 2889 400 963 2890 388 963 2891 400 964 2892 401 964 2893 389 964 2894 401 965 2895 402 965 2896 390 965 2897 390 966 2898 402 966 2899 403 966 2900 391 967 2901 403 967 2902 404 967 2903 392 968 2904 404 968 2905 405 968 2906 405 969 2907 406 969 2908 394 969 2909 406 970 2910 407 970 2911 395 970 2912 407 971 2913 396 971 2914 384 971 2915 396 972 2916 408 972 2917 409 972 2918 409 973 2919 410 973 2920 398 973 2921 410 974 2922 411 974 2923 399 974 2924 399 975 2925 411 975 2926 412 975 2927 400 976 2928 412 976 2929 413 976 2930 413 977 2931 414 977 2932 402 977 2933 414 978 2934 415 978 2935 403 978 2936 415 979 2937 416 979 2938 404 979 2939 416 980 2940 417 980 2941 405 980 2942 405 981 2943 417 981 2944 418 981 2945 406 982 2946 418 982 2947 419 982 2948 419 983 2949 408 983 2950 396 983 2951 408 984 2952 420 984 2953 421 984 2954 421 985 2955 422 985 2956 410 985 2957 422 986 2958 423 986 2959 411 986 2960 423 987 2961 424 987 2962 412 987 2963 412 988 2964 424 988 2965 425 988 2966 425 989 2967 426 989 2968 414 989 2969 414 990 2970 426 990 2971 427 990 2972 427 991 2973 428 991 2974 416 991 2975 416 992 2976 428 992 2977 429 992 2978 429 993 2979 430 993 2980 418 993 2981 430 994 2982 431 994 2983 419 994 2984 431 995 2985 420 995 2986 408 995 2987 432 996 2988 433 996 2989 421 996 2990 433 997 2991 434 997 2992 422 997 2993 434 998 2994 435 998 2995 423 998 2996 423 999 2997 435 999 2998 436 999 2999 436 1000 3000 437 1000 3001 425 1000 3002 425 1001 3003 437 1001 3004 438 1001 3005 438 1002 3006 439 1002 3007 427 1002 3008 439 1003 3009 440 1003 3010 428 1003 3011 440 1004 3012 441 1004 3013 429 1004 3014 441 1005 3015 442 1005 3016 430 1005 3017 430 1006 3018 442 1006 3019 443 1006 3020 443 1007 3021 432 1007 3022 420 1007 3023 444 1008 3024 445 1008 3025 433 1008 3026 445 1009 3027 446 1009 3028 434 1009 3029 434 1010 3030 446 1010 3031 447 1010 3032 447 1011 3033 448 1011 3034 436 1011 3035 448 1012 3036 449 1012 3037 437 1012 3038 449 1013 3039 450 1013 3040 438 1013 3041 450 1014 3042 451 1014 3043 439 1014 3044 439 1015 3045 451 1015 3046 452 1015 3047 440 1016 3048 452 1016 3049 453 1016 3050 453 1017 3051 454 1017 3052 442 1017 3053 454 1018 3054 455 1018 3055 443 1018 3056 455 1019 3057 444 1019 3058 432 1019 3059 456 1020 3060 457 1020 3061 445 1020 3062 457 1021 3063 458 1021 3064 446 1021 3065 458 1022 3066 459 1022 3067 447 1022 3068 459 1023 3069 460 1023 3070 448 1023 3071 448 1024 3072 460 1024 3073 461 1024 3074 461 1025 3075 462 1025 3076 450 1025 3077 462 1026 3078 463 1026 3079 451 1026 3080 463 1027 3081 464 1027 3082 452 1027 3083 452 1028 3084 464 1028 3085 465 1028 3086 453 1029 3087 465 1029 3088 466 1029 3089 454 1030 3090 466 1030 3091 467 1030 3092 467 1031 3093 456 1031 3094 444 1031 3095 468 1032 3096 469 1032 3097 457 1032 3098 469 1033 3099 470 1033 3100 458 1033 3101 470 1034 3102 471 1034 3103 459 1034 3104 459 1035 3105 471 1035 3106 472 1035 3107 472 1036 3108 473 1036 3109 461 1036 3110 461 1037 3111 473 1037 3112 474 1037 3113 474 1038 3114 475 1038 3115 463 1038 3116 475 1039 3117 476 1039 3118 464 1039 3119 476 1040 3120 477 1040 3121 465 1040 3122 477 1041 3123 478 1041 3124 466 1041 3125 466 1042 3126 478 1042 3127 479 1042 3128 467 1043 3129 479 1043 3130 468 1043 3131 480 1044 3132 481 1044 3133 469 1044 3134 469 1045 3135 481 1045 3136 482 1045 3137 470 1046 3138 482 1046 3139 483 1046 3140 471 1047 3141 483 1047 3142 484 1047 3143 472 1048 3144 484 1048 3145 485 1048 3146 473 1049 3147 485 1049 3148 486 1049 3149 486 1050 3150 487 1050 3151 475 1050 3152 487 1051 3153 488 1051 3154 476 1051 3155 488 1052 3156 489 1052 3157 477 1052 3158 489 1053 3159 490 1053 3160 478 1053 3161 490 1054 3162 491 1054 3163 479 1054 3164 491 1055 3165 480 1055 3166 468 1055 3167 480 1056 3168 492 1056 3169 493 1056 3170 493 1057 3171 494 1057 3172 482 1057 3173 494 1058 3174 495 1058 3175 483 1058 3176 495 1059 3177 496 1059 3178 484 1059 3179 496 1060 3180 497 1060 3181 485 1060 3182 497 1061 3183 498 1061 3184 486 1061 3185 486 1062 3186 498 1062 3187 499 1062 3188 487 1063 3189 499 1063 3190 500 1063 3191 488 1064 3192 500 1064 3193 501 1064 3194 489 1065 3195 501 1065 3196 502 1065 3197 490 1066 3198 502 1066 3199 503 1066 3200 503 1067 3201 492 1067 3202 480 1067 3203 492 1068 3204 504 1068 3205 505 1068 3206 505 1069 3207 506 1069 3208 494 1069 3209 494 1070 3210 506 1070 3211 507 1070 3212 495 1071 3213 507 1071 3214 508 1071 3215 496 1072 3216 508 1072 3217 509 1072 3218 497 1073 3219 509 1073 3220 510 1073 3221 510 1074 3222 511 1074 3223 499 1074 3224 511 1075 3225 512 1075 3226 500 1075 3227 512 1076 3228 513 1076 3229 501 1076 3230 513 1077 3231 514 1077 3232 502 1077 3233 514 1078 3234 515 1078 3235 503 1078 3236 515 1079 3237 504 1079 3238 492 1079 3239 504 1080 3240 516 1080 3241 517 1080 3242 517 1081 3243 518 1081 3244 506 1081 3245 506 1082 3246 518 1082 3247 519 1082 3248 519 1083 3249 520 1083 3250 508 1083 3251 520 1084 3252 521 1084 3253 509 1084 3254 509 1085 3255 521 1085 3256 522 1085 3257 522 1086 3258 523 1086 3259 511 1086 3260 511 1087 3261 523 1087 3262 524 1087 3263 524 1088 3264 525 1088 3265 513 1088 3266 525 1089 3267 526 1089 3268 514 1089 3269 514 1090 3270 526 1090 3271 527 1090 3272 527 1091 3273 516 1091 3274 504 1091 3275 516 1092 3276 528 1092 3277 529 1092 3278 529 1093 3279 530 1093 3280 518 1093 3281 530 1094 3282 531 1094 3283 519 1094 3284 519 1095 3285 531 1095 3286 532 1095 3287 532 1096 3288 533 1096 3289 521 1096 3290 521 1097 3291 533 1097 3292 534 1097 3293 534 1098 3294 535 1098 3295 523 1098 3296 523 1099 3297 535 1099 3298 536 1099 3299 536 1100 3300 537 1100 3301 525 1100 3302 537 1101 3303 538 1101 3304 526 1101 3305 526 1102 3306 538 1102 3307 539 1102 3308 539 1103 3309 528 1103 3310 516 1103 3311 528 1104 3312 540 1104 3313 541 1104 3314 529 1105 3315 541 1105 3316 542 1105 3317 530 1106 3318 542 1106 3319 543 1106 3320 531 1107 3321 543 1107 3322 544 1107 3323 544 1108 3324 545 1108 3325 533 1108 3326 533 1109 3327 545 1109 3328 546 1109 3329 546 1110 3330 547 1110 3331 535 1110 3332 547 1111 3333 548 1111 3334 536 1111 3335 548 1112 3336 549 1112 3337 537 1112 3338 549 1113 3339 550 1113 3340 538 1113 3341 550 1114 3342 551 1114 3343 539 1114 3344 551 1115 3345 540 1115 3346 528 1115 3347 552 1116 3348 553 1116 3349 541 1116 3350 553 1117 3351 554 1117 3352 542 1117 3353 554 1118 3354 555 1118 3355 543 1118 3356 555 1119 3357 556 1119 3358 544 1119 3359 556 1120 3360 557 1120 3361 545 1120 3362 557 1121 3363 558 1121 3364 546 1121 3365 546 1122 3366 558 1122 3367 559 1122 3368 547 1123 3369 559 1123 3370 560 1123 3371 560 1124 3372 561 1124 3373 549 1124 3374 549 1125 3375 561 1125 3376 562 1125 3377 562 1126 3378 563 1126 3379 551 1126 3380 551 1127 3381 563 1127 3382 552 1127 3383 564 1128 3384 565 1128 3385 553 1128 3386 553 1129 3387 565 1129 3388 566 1129 3389 554 1130 3390 566 1130 3391 567 1130 3392 555 1131 3393 567 1131 3394 568 1131 3395 556 1132 3396 568 1132 3397 569 1132 3398 557 1133 3399 569 1133 3400 570 1133 3401 570 1134 3402 571 1134 3403 559 1134 3404 571 1135 3405 572 1135 3406 560 1135 3407 572 1136 3408 573 1136 3409 561 1136 3410 573 1137 3411 574 1137 3412 562 1137 3413 574 1138 3414 575 1138 3415 563 1138 3416 575 1139 3417 564 1139 3418 552 1139 3419 0 1140 3420 1 1140 3421 565 1140 3422 1 1141 3423 2 1141 3424 566 1141 3425 2 1142 3426 3 1142 3427 567 1142 3428 3 1143 3429 4 1143 3430 568 1143 3431 568 1144 3432 4 1144 3433 5 1144 3434 5 1145 3435 6 1145 3436 570 1145 3437 570 1146 3438 6 1146 3439 7 1146 3440 7 1147 3441 8 1147 3442 572 1147 3443 572 1148 3444 8 1148 3445 9 1148 3446 573 1149 3447 9 1149 3448 10 1149 3449 574 1150 3450 10 1150 3451 11 1150 3452 575 1151 3453 11 1151 3454 0 1151 3455

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/sdformat_test_files/models/geometry_mesh_obj/geometry_mesh_obj.sdf b/sdformat_test_files/models/geometry_mesh_obj/geometry_mesh_obj.sdf new file mode 100644 index 00000000..e4757b08 --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_obj/geometry_mesh_obj.sdf @@ -0,0 +1,34 @@ + + + + + + + + model://geometry_mesh_obj/torus.obj + 0.1 0.1 0.1 + + + + + + + model://geometry_mesh_obj/torus.obj + 0.1 0.1 0.1 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/geometry_mesh_obj/model.config b/sdformat_test_files/models/geometry_mesh_obj/model.config new file mode 100644 index 00000000..8b0d7d96 --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_obj/model.config @@ -0,0 +1,15 @@ + + + geometry_mesh_obj + 1.0 + geometry_mesh_obj.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + A single link using a Wavefront OBJ mesh. + + diff --git a/sdformat_test_files/models/geometry_mesh_obj/torus.mtl b/sdformat_test_files/models/geometry_mesh_obj/torus.mtl new file mode 100644 index 00000000..ac53ddfe --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_obj/torus.mtl @@ -0,0 +1,12 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl Material +Ns 323.999994 +Ka 1.000000 1.000000 1.000000 +Kd 0.000000 0.028922 0.800000 +Ks 0.500000 0.500000 0.500000 +Ke 0.000000 0.000000 0.000000 +Ni 1.000000 +d 1.000000 +illum 2 diff --git a/sdformat_test_files/models/geometry_mesh_obj/torus.obj b/sdformat_test_files/models/geometry_mesh_obj/torus.obj new file mode 100644 index 00000000..1f398c43 --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_obj/torus.obj @@ -0,0 +1,2083 @@ +# Blender v2.83.3 OBJ File: '' +# www.blender.org +mtllib torus.mtl +o Torus +v 1.250000 0.000000 0.000000 +v 1.216506 0.125000 0.000000 +v 1.125000 0.216506 0.000000 +v 1.000000 0.250000 0.000000 +v 0.875000 0.216506 0.000000 +v 0.783494 0.125000 0.000000 +v 0.750000 0.000000 0.000000 +v 0.783494 -0.125000 0.000000 +v 0.875000 -0.216506 0.000000 +v 1.000000 -0.250000 0.000000 +v 1.125000 -0.216506 0.000000 +v 1.216506 -0.125000 0.000000 +v 1.239306 0.000000 -0.163158 +v 1.206099 0.125000 -0.158786 +v 1.115376 0.216506 -0.146842 +v 0.991445 0.250000 -0.130526 +v 0.867514 0.216506 -0.114210 +v 0.776791 0.125000 -0.102266 +v 0.743584 0.000000 -0.097895 +v 0.776791 -0.125000 -0.102266 +v 0.867514 -0.216506 -0.114210 +v 0.991445 -0.250000 -0.130526 +v 1.115376 -0.216506 -0.146842 +v 1.206099 -0.125000 -0.158786 +v 1.207407 0.000000 -0.323524 +v 1.175055 0.125000 -0.314855 +v 1.086667 0.216506 -0.291171 +v 0.965926 0.250000 -0.258819 +v 0.845185 0.216506 -0.226467 +v 0.756797 0.125000 -0.202783 +v 0.724444 0.000000 -0.194114 +v 0.756797 -0.125000 -0.202783 +v 0.845185 -0.216506 -0.226467 +v 0.965926 -0.250000 -0.258819 +v 1.086667 -0.216506 -0.291171 +v 1.175055 -0.125000 -0.314855 +v 1.154849 0.000000 -0.478354 +v 1.123905 0.125000 -0.465537 +v 1.039364 0.216506 -0.430519 +v 0.923880 0.250000 -0.382683 +v 0.808395 0.216506 -0.334848 +v 0.723854 0.125000 -0.299830 +v 0.692910 0.000000 -0.287013 +v 0.723854 -0.125000 -0.299830 +v 0.808395 -0.216506 -0.334848 +v 0.923880 -0.250000 -0.382683 +v 1.039364 -0.216506 -0.430519 +v 1.123905 -0.125000 -0.465537 +v 1.082532 0.000000 -0.625000 +v 1.053525 0.125000 -0.608253 +v 0.974279 0.216506 -0.562500 +v 0.866025 0.250000 -0.500000 +v 0.757772 0.216506 -0.437500 +v 0.678525 0.125000 -0.391747 +v 0.649519 0.000000 -0.375000 +v 0.678525 -0.125000 -0.391747 +v 0.757772 -0.216506 -0.437500 +v 0.866025 -0.250000 -0.500000 +v 0.974279 -0.216506 -0.562500 +v 1.053525 -0.125000 -0.608253 +v 0.991692 0.000000 -0.760952 +v 0.965119 0.125000 -0.740562 +v 0.892523 0.216506 -0.684856 +v 0.793353 0.250000 -0.608761 +v 0.694184 0.216506 -0.532666 +v 0.621587 0.125000 -0.476961 +v 0.595015 0.000000 -0.456571 +v 0.621587 -0.125000 -0.476961 +v 0.694184 -0.216506 -0.532666 +v 0.793353 -0.250000 -0.608761 +v 0.892523 -0.216506 -0.684856 +v 0.965119 -0.125000 -0.740562 +v 0.883883 0.000000 -0.883884 +v 0.860200 0.125000 -0.860200 +v 0.795495 0.216506 -0.795495 +v 0.707107 0.250000 -0.707107 +v 0.618718 0.216506 -0.618719 +v 0.554014 0.125000 -0.554014 +v 0.530330 0.000000 -0.530330 +v 0.554014 -0.125000 -0.554014 +v 0.618718 -0.216506 -0.618719 +v 0.707107 -0.250000 -0.707107 +v 0.795495 -0.216506 -0.795495 +v 0.860200 -0.125000 -0.860200 +v 0.760952 0.000000 -0.991691 +v 0.740562 0.125000 -0.965119 +v 0.684857 0.216506 -0.892522 +v 0.608762 0.250000 -0.793353 +v 0.532666 0.216506 -0.694184 +v 0.476961 0.125000 -0.621587 +v 0.456571 0.000000 -0.595015 +v 0.476961 -0.125000 -0.621587 +v 0.532666 -0.216506 -0.694184 +v 0.608762 -0.250000 -0.793353 +v 0.684857 -0.216506 -0.892522 +v 0.740562 -0.125000 -0.965119 +v 0.625000 0.000000 -1.082532 +v 0.608253 0.125000 -1.053525 +v 0.562500 0.216506 -0.974279 +v 0.500000 0.250000 -0.866025 +v 0.437500 0.216506 -0.757772 +v 0.391747 0.125000 -0.678525 +v 0.375000 0.000000 -0.649519 +v 0.391747 -0.125000 -0.678525 +v 0.437500 -0.216506 -0.757772 +v 0.500000 -0.250000 -0.866025 +v 0.562500 -0.216506 -0.974279 +v 0.608253 -0.125000 -1.053525 +v 0.478355 0.000000 -1.154849 +v 0.465537 0.125000 -1.123905 +v 0.430519 0.216506 -1.039364 +v 0.382684 0.250000 -0.923879 +v 0.334848 0.216506 -0.808394 +v 0.299830 0.125000 -0.723854 +v 0.287013 0.000000 -0.692910 +v 0.299830 -0.125000 -0.723854 +v 0.334848 -0.216506 -0.808394 +v 0.382684 -0.250000 -0.923879 +v 0.430519 -0.216506 -1.039364 +v 0.465537 -0.125000 -1.123905 +v 0.323524 0.000000 -1.207407 +v 0.314855 0.125000 -1.175055 +v 0.291171 0.216506 -1.086667 +v 0.258819 0.250000 -0.965926 +v 0.226467 0.216506 -0.845185 +v 0.202783 0.125000 -0.756797 +v 0.194114 0.000000 -0.724444 +v 0.202783 -0.125000 -0.756797 +v 0.226467 -0.216506 -0.845185 +v 0.258819 -0.250000 -0.965926 +v 0.291171 -0.216506 -1.086667 +v 0.314855 -0.125000 -1.175055 +v 0.163158 0.000000 -1.239306 +v 0.158786 0.125000 -1.206099 +v 0.146842 0.216506 -1.115376 +v 0.130526 0.250000 -0.991445 +v 0.114210 0.216506 -0.867514 +v 0.102266 0.125000 -0.776791 +v 0.097895 0.000000 -0.743584 +v 0.102266 -0.125000 -0.776791 +v 0.114210 -0.216506 -0.867514 +v 0.130526 -0.250000 -0.991445 +v 0.146842 -0.216506 -1.115376 +v 0.158786 -0.125000 -1.206099 +v 0.000000 0.000000 -1.250000 +v 0.000000 0.125000 -1.216506 +v 0.000000 0.216506 -1.125000 +v 0.000000 0.250000 -1.000000 +v 0.000000 0.216506 -0.875000 +v 0.000000 0.125000 -0.783494 +v 0.000000 0.000000 -0.750000 +v 0.000000 -0.125000 -0.783494 +v 0.000000 -0.216506 -0.875000 +v 0.000000 -0.250000 -1.000000 +v 0.000000 -0.216506 -1.125000 +v 0.000000 -0.125000 -1.216506 +v -0.163158 0.000000 -1.239306 +v -0.158786 0.125000 -1.206099 +v -0.146842 0.216506 -1.115375 +v -0.130526 0.250000 -0.991445 +v -0.114211 0.216506 -0.867514 +v -0.102267 0.125000 -0.776791 +v -0.097895 0.000000 -0.743584 +v -0.102267 -0.125000 -0.776791 +v -0.114211 -0.216506 -0.867514 +v -0.130526 -0.250000 -0.991445 +v -0.146842 -0.216506 -1.115375 +v -0.158786 -0.125000 -1.206099 +v -0.323524 0.000000 -1.207407 +v -0.314855 0.125000 -1.175055 +v -0.291171 0.216506 -1.086667 +v -0.258819 0.250000 -0.965926 +v -0.226467 0.216506 -0.845185 +v -0.202783 0.125000 -0.756797 +v -0.194114 0.000000 -0.724444 +v -0.202783 -0.125000 -0.756797 +v -0.226467 -0.216506 -0.845185 +v -0.258819 -0.250000 -0.965926 +v -0.291171 -0.216506 -1.086667 +v -0.314855 -0.125000 -1.175055 +v -0.478354 0.000000 -1.154849 +v -0.465537 0.125000 -1.123905 +v -0.430519 0.216506 -1.039364 +v -0.382684 0.250000 -0.923880 +v -0.334848 0.216506 -0.808395 +v -0.299830 0.125000 -0.723854 +v -0.287013 0.000000 -0.692910 +v -0.299830 -0.125000 -0.723854 +v -0.334848 -0.216506 -0.808395 +v -0.382684 -0.250000 -0.923880 +v -0.430519 -0.216506 -1.039364 +v -0.465537 -0.125000 -1.123905 +v -0.625000 0.000000 -1.082532 +v -0.608253 0.125000 -1.053526 +v -0.562500 0.216506 -0.974279 +v -0.500000 0.250000 -0.866026 +v -0.437500 0.216506 -0.757772 +v -0.391747 0.125000 -0.678525 +v -0.375000 0.000000 -0.649519 +v -0.391747 -0.125000 -0.678525 +v -0.437500 -0.216506 -0.757772 +v -0.500000 -0.250000 -0.866026 +v -0.562500 -0.216506 -0.974279 +v -0.608253 -0.125000 -1.053526 +v -0.760952 0.000000 -0.991692 +v -0.740562 0.125000 -0.965119 +v -0.684857 0.216506 -0.892522 +v -0.608761 0.250000 -0.793353 +v -0.532666 0.216506 -0.694184 +v -0.476961 0.125000 -0.621587 +v -0.456571 0.000000 -0.595015 +v -0.476961 -0.125000 -0.621587 +v -0.532666 -0.216506 -0.694184 +v -0.608761 -0.250000 -0.793353 +v -0.684857 -0.216506 -0.892522 +v -0.740562 -0.125000 -0.965119 +v -0.883884 0.000000 -0.883883 +v -0.860200 0.125000 -0.860200 +v -0.795495 0.216506 -0.795495 +v -0.707107 0.250000 -0.707107 +v -0.618719 0.216506 -0.618718 +v -0.554014 0.125000 -0.554013 +v -0.530330 0.000000 -0.530330 +v -0.554014 -0.125000 -0.554013 +v -0.618719 -0.216506 -0.618718 +v -0.707107 -0.250000 -0.707107 +v -0.795495 -0.216506 -0.795495 +v -0.860200 -0.125000 -0.860200 +v -0.991692 0.000000 -0.760952 +v -0.965119 0.125000 -0.740562 +v -0.892522 0.216506 -0.684857 +v -0.793353 0.250000 -0.608761 +v -0.694184 0.216506 -0.532666 +v -0.621587 0.125000 -0.476961 +v -0.595015 0.000000 -0.456571 +v -0.621587 -0.125000 -0.476961 +v -0.694184 -0.216506 -0.532666 +v -0.793353 -0.250000 -0.608761 +v -0.892522 -0.216506 -0.684857 +v -0.965119 -0.125000 -0.740562 +v -1.082532 0.000000 -0.625000 +v -1.053525 0.125000 -0.608253 +v -0.974278 0.216506 -0.562500 +v -0.866025 0.250000 -0.500000 +v -0.757772 0.216506 -0.437500 +v -0.678525 0.125000 -0.391747 +v -0.649519 0.000000 -0.375000 +v -0.678525 -0.125000 -0.391747 +v -0.757772 -0.216506 -0.437500 +v -0.866025 -0.250000 -0.500000 +v -0.974278 -0.216506 -0.562500 +v -1.053525 -0.125000 -0.608253 +v -1.154849 0.000000 -0.478354 +v -1.123905 0.125000 -0.465537 +v -1.039364 0.216506 -0.430519 +v -0.923880 0.250000 -0.382683 +v -0.808395 0.216506 -0.334848 +v -0.723854 0.125000 -0.299830 +v -0.692910 0.000000 -0.287013 +v -0.723854 -0.125000 -0.299830 +v -0.808395 -0.216506 -0.334848 +v -0.923880 -0.250000 -0.382683 +v -1.039364 -0.216506 -0.430519 +v -1.123905 -0.125000 -0.465537 +v -1.207407 0.000000 -0.323524 +v -1.175055 0.125000 -0.314855 +v -1.086667 0.216506 -0.291171 +v -0.965926 0.250000 -0.258819 +v -0.845185 0.216506 -0.226467 +v -0.756797 0.125000 -0.202783 +v -0.724444 0.000000 -0.194114 +v -0.756797 -0.125000 -0.202783 +v -0.845185 -0.216506 -0.226467 +v -0.965926 -0.250000 -0.258819 +v -1.086667 -0.216506 -0.291171 +v -1.175055 -0.125000 -0.314855 +v -1.239306 0.000000 -0.163158 +v -1.206099 0.125000 -0.158786 +v -1.115375 0.216506 -0.146842 +v -0.991445 0.250000 -0.130526 +v -0.867514 0.216506 -0.114211 +v -0.776791 0.125000 -0.102267 +v -0.743584 0.000000 -0.097895 +v -0.776791 -0.125000 -0.102267 +v -0.867514 -0.216506 -0.114211 +v -0.991445 -0.250000 -0.130526 +v -1.115375 -0.216506 -0.146842 +v -1.206099 -0.125000 -0.158786 +v -1.250000 0.000000 -0.000000 +v -1.216506 0.125000 -0.000000 +v -1.125000 0.216506 -0.000000 +v -1.000000 0.250000 -0.000000 +v -0.875000 0.216506 -0.000000 +v -0.783494 0.125000 -0.000000 +v -0.750000 0.000000 -0.000000 +v -0.783494 -0.125000 -0.000000 +v -0.875000 -0.216506 -0.000000 +v -1.000000 -0.250000 -0.000000 +v -1.125000 -0.216506 -0.000000 +v -1.216506 -0.125000 -0.000000 +v -1.239306 0.000000 0.163158 +v -1.206099 0.125000 0.158786 +v -1.115375 0.216506 0.146842 +v -0.991445 0.250000 0.130526 +v -0.867514 0.216506 0.114211 +v -0.776791 0.125000 0.102267 +v -0.743584 0.000000 0.097895 +v -0.776791 -0.125000 0.102267 +v -0.867514 -0.216506 0.114211 +v -0.991445 -0.250000 0.130526 +v -1.115375 -0.216506 0.146842 +v -1.206099 -0.125000 0.158786 +v -1.207407 0.000000 0.323524 +v -1.175055 0.125000 0.314855 +v -1.086667 0.216506 0.291171 +v -0.965926 0.250000 0.258819 +v -0.845185 0.216506 0.226467 +v -0.756797 0.125000 0.202783 +v -0.724444 0.000000 0.194114 +v -0.756797 -0.125000 0.202783 +v -0.845185 -0.216506 0.226467 +v -0.965926 -0.250000 0.258819 +v -1.086667 -0.216506 0.291171 +v -1.175055 -0.125000 0.314855 +v -1.154850 0.000000 0.478354 +v -1.123906 0.125000 0.465536 +v -1.039365 0.216506 0.430518 +v -0.923880 0.250000 0.382683 +v -0.808395 0.216506 0.334848 +v -0.723854 0.125000 0.299830 +v -0.692910 0.000000 0.287012 +v -0.723854 -0.125000 0.299830 +v -0.808395 -0.216506 0.334848 +v -0.923880 -0.250000 0.382683 +v -1.039365 -0.216506 0.430518 +v -1.123906 -0.125000 0.465536 +v -1.082532 0.000000 0.625000 +v -1.053526 0.125000 0.608253 +v -0.974279 0.216506 0.562500 +v -0.866026 0.250000 0.500000 +v -0.757772 0.216506 0.437500 +v -0.678525 0.125000 0.391747 +v -0.649519 0.000000 0.375000 +v -0.678525 -0.125000 0.391747 +v -0.757772 -0.216506 0.437500 +v -0.866026 -0.250000 0.500000 +v -0.974279 -0.216506 0.562500 +v -1.053526 -0.125000 0.608253 +v -0.991692 0.000000 0.760952 +v -0.965119 0.125000 0.740562 +v -0.892522 0.216506 0.684857 +v -0.793353 0.250000 0.608761 +v -0.694184 0.216506 0.532666 +v -0.621587 0.125000 0.476961 +v -0.595015 0.000000 0.456571 +v -0.621587 -0.125000 0.476961 +v -0.694184 -0.216506 0.532666 +v -0.793353 -0.250000 0.608761 +v -0.892522 -0.216506 0.684857 +v -0.965119 -0.125000 0.740562 +v -0.883884 0.000000 0.883883 +v -0.860200 0.125000 0.860200 +v -0.795495 0.216506 0.795495 +v -0.707107 0.250000 0.707107 +v -0.618719 0.216506 0.618718 +v -0.554014 0.125000 0.554013 +v -0.530330 0.000000 0.530330 +v -0.554014 -0.125000 0.554013 +v -0.618719 -0.216506 0.618718 +v -0.707107 -0.250000 0.707107 +v -0.795495 -0.216506 0.795495 +v -0.860200 -0.125000 0.860200 +v -0.760952 0.000000 0.991691 +v -0.740563 0.125000 0.965119 +v -0.684857 0.216506 0.892522 +v -0.608762 0.250000 0.793353 +v -0.532667 0.216506 0.694184 +v -0.476961 0.125000 0.621587 +v -0.456571 0.000000 0.595015 +v -0.476961 -0.125000 0.621587 +v -0.532667 -0.216506 0.694184 +v -0.608762 -0.250000 0.793353 +v -0.684857 -0.216506 0.892522 +v -0.740563 -0.125000 0.965119 +v -0.625000 0.000000 1.082532 +v -0.608253 0.125000 1.053526 +v -0.562500 0.216506 0.974279 +v -0.500000 0.250000 0.866026 +v -0.437500 0.216506 0.757772 +v -0.391747 0.125000 0.678525 +v -0.375000 0.000000 0.649519 +v -0.391747 -0.125000 0.678525 +v -0.437500 -0.216506 0.757772 +v -0.500000 -0.250000 0.866026 +v -0.562500 -0.216506 0.974279 +v -0.608253 -0.125000 1.053526 +v -0.478354 0.000000 1.154849 +v -0.465537 0.125000 1.123905 +v -0.430519 0.216506 1.039364 +v -0.382684 0.250000 0.923880 +v -0.334848 0.216506 0.808395 +v -0.299830 0.125000 0.723854 +v -0.287013 0.000000 0.692910 +v -0.299830 -0.125000 0.723854 +v -0.334848 -0.216506 0.808395 +v -0.382684 -0.250000 0.923880 +v -0.430519 -0.216506 1.039364 +v -0.465537 -0.125000 1.123905 +v -0.323524 0.000000 1.207407 +v -0.314855 0.125000 1.175055 +v -0.291172 0.216506 1.086666 +v -0.258819 0.250000 0.965926 +v -0.226467 0.216506 0.845185 +v -0.202783 0.125000 0.756797 +v -0.194115 0.000000 0.724444 +v -0.202783 -0.125000 0.756797 +v -0.226467 -0.216506 0.845185 +v -0.258819 -0.250000 0.965926 +v -0.291172 -0.216506 1.086666 +v -0.314855 -0.125000 1.175055 +v -0.163158 0.000000 1.239306 +v -0.158787 0.125000 1.206099 +v -0.146843 0.216506 1.115375 +v -0.130527 0.250000 0.991445 +v -0.114211 0.216506 0.867514 +v -0.102267 0.125000 0.776791 +v -0.097895 0.000000 0.743584 +v -0.102267 -0.125000 0.776791 +v -0.114211 -0.216506 0.867514 +v -0.130527 -0.250000 0.991445 +v -0.146843 -0.216506 1.115375 +v -0.158787 -0.125000 1.206099 +v 0.000000 0.000000 1.250000 +v 0.000000 0.125000 1.216506 +v 0.000000 0.216506 1.125000 +v 0.000000 0.250000 1.000000 +v 0.000000 0.216506 0.875000 +v 0.000000 0.125000 0.783494 +v 0.000000 0.000000 0.750000 +v 0.000000 -0.125000 0.783494 +v 0.000000 -0.216506 0.875000 +v 0.000000 -0.250000 1.000000 +v 0.000000 -0.216506 1.125000 +v 0.000000 -0.125000 1.216506 +v 0.163158 0.000000 1.239306 +v 0.158786 0.125000 1.206099 +v 0.146842 0.216506 1.115376 +v 0.130526 0.250000 0.991445 +v 0.114210 0.216506 0.867514 +v 0.102266 0.125000 0.776791 +v 0.097895 0.000000 0.743584 +v 0.102266 -0.125000 0.776791 +v 0.114210 -0.216506 0.867514 +v 0.130526 -0.250000 0.991445 +v 0.146842 -0.216506 1.115376 +v 0.158786 -0.125000 1.206099 +v 0.323523 0.000000 1.207407 +v 0.314854 0.125000 1.175055 +v 0.291171 0.216506 1.086667 +v 0.258819 0.250000 0.965926 +v 0.226466 0.216506 0.845185 +v 0.202783 0.125000 0.756797 +v 0.194114 0.000000 0.724444 +v 0.202783 -0.125000 0.756797 +v 0.226466 -0.216506 0.845185 +v 0.258819 -0.250000 0.965926 +v 0.291171 -0.216506 1.086667 +v 0.314854 -0.125000 1.175055 +v 0.478355 0.000000 1.154849 +v 0.465537 0.125000 1.123905 +v 0.430519 0.216506 1.039364 +v 0.382684 0.250000 0.923879 +v 0.334848 0.216506 0.808394 +v 0.299830 0.125000 0.723854 +v 0.287013 0.000000 0.692910 +v 0.299830 -0.125000 0.723854 +v 0.334848 -0.216506 0.808394 +v 0.382684 -0.250000 0.923879 +v 0.430519 -0.216506 1.039364 +v 0.465537 -0.125000 1.123905 +v 0.625000 0.000000 1.082532 +v 0.608253 0.125000 1.053525 +v 0.562500 0.216506 0.974279 +v 0.500000 0.250000 0.866025 +v 0.437500 0.216506 0.757772 +v 0.391747 0.125000 0.678525 +v 0.375000 0.000000 0.649519 +v 0.391747 -0.125000 0.678525 +v 0.437500 -0.216506 0.757772 +v 0.500000 -0.250000 0.866025 +v 0.562500 -0.216506 0.974279 +v 0.608253 -0.125000 1.053525 +v 0.760952 0.000000 0.991692 +v 0.740562 0.125000 0.965120 +v 0.684856 0.216506 0.892523 +v 0.608761 0.250000 0.793353 +v 0.532666 0.216506 0.694184 +v 0.476961 0.125000 0.621587 +v 0.456571 0.000000 0.595015 +v 0.476961 -0.125000 0.621587 +v 0.532666 -0.216506 0.694184 +v 0.608761 -0.250000 0.793353 +v 0.684856 -0.216506 0.892523 +v 0.740562 -0.125000 0.965120 +v 0.883883 0.000000 0.883884 +v 0.860199 0.125000 0.860200 +v 0.795495 0.216506 0.795496 +v 0.707106 0.250000 0.707107 +v 0.618718 0.216506 0.618719 +v 0.554013 0.125000 0.554014 +v 0.530330 0.000000 0.530330 +v 0.554013 -0.125000 0.554014 +v 0.618718 -0.216506 0.618719 +v 0.707106 -0.250000 0.707107 +v 0.795495 -0.216506 0.795496 +v 0.860199 -0.125000 0.860200 +v 0.991692 0.000000 0.760952 +v 0.965119 0.125000 0.740562 +v 0.892523 0.216506 0.684856 +v 0.793353 0.250000 0.608761 +v 0.694184 0.216506 0.532666 +v 0.621587 0.125000 0.476961 +v 0.595015 0.000000 0.456571 +v 0.621587 -0.125000 0.476961 +v 0.694184 -0.216506 0.532666 +v 0.793353 -0.250000 0.608761 +v 0.892523 -0.216506 0.684856 +v 0.965119 -0.125000 0.740562 +v 1.082532 0.000000 0.625000 +v 1.053525 0.125000 0.608253 +v 0.974279 0.216506 0.562500 +v 0.866025 0.250000 0.500000 +v 0.757772 0.216506 0.437500 +v 0.678525 0.125000 0.391747 +v 0.649519 0.000000 0.375000 +v 0.678525 -0.125000 0.391747 +v 0.757772 -0.216506 0.437500 +v 0.866025 -0.250000 0.500000 +v 0.974279 -0.216506 0.562500 +v 1.053525 -0.125000 0.608253 +v 1.154849 0.000000 0.478355 +v 1.123905 0.125000 0.465537 +v 1.039364 0.216506 0.430519 +v 0.923879 0.250000 0.382684 +v 0.808394 0.216506 0.334848 +v 0.723854 0.125000 0.299830 +v 0.692910 0.000000 0.287013 +v 0.723854 -0.125000 0.299830 +v 0.808394 -0.216506 0.334848 +v 0.923879 -0.250000 0.382684 +v 1.039364 -0.216506 0.430519 +v 1.123905 -0.125000 0.465537 +v 1.207407 0.000000 0.323523 +v 1.175055 0.125000 0.314855 +v 1.086667 0.216506 0.291171 +v 0.965926 0.250000 0.258819 +v 0.845185 0.216506 0.226466 +v 0.756797 0.125000 0.202783 +v 0.724444 0.000000 0.194114 +v 0.756797 -0.125000 0.202783 +v 0.845185 -0.216506 0.226466 +v 0.965926 -0.250000 0.258819 +v 1.086667 -0.216506 0.291171 +v 1.175055 -0.125000 0.314855 +v 1.239306 0.000000 0.163158 +v 1.206099 0.125000 0.158786 +v 1.115376 0.216506 0.146842 +v 0.991445 0.250000 0.130526 +v 0.867514 0.216506 0.114210 +v 0.776791 0.125000 0.102266 +v 0.743584 0.000000 0.097895 +v 0.776791 -0.125000 0.102266 +v 0.867514 -0.216506 0.114210 +v 0.991445 -0.250000 0.130526 +v 1.115376 -0.216506 0.146842 +v 1.206099 -0.125000 0.158786 +vt 0.500000 0.500000 +vt 0.520833 0.500000 +vt 0.520833 0.583333 +vt 0.500000 0.583333 +vt 0.520833 0.666667 +vt 0.500000 0.666667 +vt 0.520833 0.750000 +vt 0.500000 0.750000 +vt 0.520833 0.833333 +vt 0.500000 0.833333 +vt 0.520833 0.916667 +vt 0.500000 0.916667 +vt 0.520833 1.000000 +vt 0.500000 1.000000 +vt 0.500000 0.000000 +vt 0.520833 0.000000 +vt 0.520833 0.083333 +vt 0.500000 0.083333 +vt 0.520833 0.166667 +vt 0.500000 0.166667 +vt 0.520833 0.250000 +vt 0.500000 0.250000 +vt 0.520833 0.333333 +vt 0.500000 0.333333 +vt 0.520833 0.416667 +vt 0.500000 0.416667 +vt 0.541667 0.500000 +vt 0.541667 0.583333 +vt 0.541667 0.666667 +vt 0.541667 0.750000 +vt 0.541667 0.833333 +vt 0.541667 0.916667 +vt 0.541667 1.000000 +vt 0.541667 0.000000 +vt 0.541667 0.083333 +vt 0.541667 0.166667 +vt 0.541667 0.250000 +vt 0.541667 0.333333 +vt 0.541667 0.416667 +vt 0.562500 0.500000 +vt 0.562500 0.583333 +vt 0.562500 0.666667 +vt 0.562500 0.750000 +vt 0.562500 0.833333 +vt 0.562500 0.916667 +vt 0.562500 1.000000 +vt 0.562500 0.000000 +vt 0.562500 0.083333 +vt 0.562500 0.166667 +vt 0.562500 0.250000 +vt 0.562500 0.333333 +vt 0.562500 0.416667 +vt 0.583333 0.500000 +vt 0.583333 0.583333 +vt 0.583333 0.666667 +vt 0.583333 0.750000 +vt 0.583333 0.833333 +vt 0.583333 0.916667 +vt 0.583333 1.000000 +vt 0.583333 0.000000 +vt 0.583333 0.083333 +vt 0.583333 0.166667 +vt 0.583333 0.250000 +vt 0.583333 0.333333 +vt 0.583333 0.416667 +vt 0.604167 0.500000 +vt 0.604167 0.583333 +vt 0.604167 0.666667 +vt 0.604167 0.750000 +vt 0.604167 0.833333 +vt 0.604167 0.916667 +vt 0.604167 1.000000 +vt 0.604167 0.000000 +vt 0.604167 0.083333 +vt 0.604167 0.166667 +vt 0.604167 0.250000 +vt 0.604167 0.333333 +vt 0.604167 0.416667 +vt 0.625000 0.500000 +vt 0.625000 0.583333 +vt 0.625000 0.666667 +vt 0.625000 0.750000 +vt 0.625000 0.833333 +vt 0.625000 0.916667 +vt 0.625000 1.000000 +vt 0.625000 0.000000 +vt 0.625000 0.083333 +vt 0.625000 0.166667 +vt 0.625000 0.250000 +vt 0.625000 0.333333 +vt 0.625000 0.416667 +vt 0.645833 0.500000 +vt 0.645833 0.583333 +vt 0.645833 0.666667 +vt 0.645833 0.750000 +vt 0.645833 0.833333 +vt 0.645833 0.916667 +vt 0.645833 1.000000 +vt 0.645833 0.000000 +vt 0.645833 0.083333 +vt 0.645833 0.166667 +vt 0.645833 0.250000 +vt 0.645833 0.333333 +vt 0.645833 0.416667 +vt 0.666667 0.500000 +vt 0.666667 0.583333 +vt 0.666667 0.666667 +vt 0.666667 0.750000 +vt 0.666667 0.833333 +vt 0.666667 0.916667 +vt 0.666667 1.000000 +vt 0.666667 0.000000 +vt 0.666667 0.083333 +vt 0.666667 0.166667 +vt 0.666667 0.250000 +vt 0.666667 0.333333 +vt 0.666667 0.416667 +vt 0.687500 0.500000 +vt 0.687500 0.583333 +vt 0.687500 0.666667 +vt 0.687500 0.750000 +vt 0.687500 0.833333 +vt 0.687500 0.916667 +vt 0.687500 1.000000 +vt 0.687500 0.000000 +vt 0.687500 0.083333 +vt 0.687500 0.166667 +vt 0.687500 0.250000 +vt 0.687500 0.333333 +vt 0.687500 0.416667 +vt 0.708333 0.500000 +vt 0.708333 0.583333 +vt 0.708333 0.666667 +vt 0.708333 0.750000 +vt 0.708333 0.833333 +vt 0.708333 0.916667 +vt 0.708333 1.000000 +vt 0.708333 0.000000 +vt 0.708333 0.083333 +vt 0.708333 0.166667 +vt 0.708333 0.250000 +vt 0.708333 0.333333 +vt 0.708333 0.416667 +vt 0.729167 0.500000 +vt 0.729167 0.583333 +vt 0.729167 0.666667 +vt 0.729167 0.750000 +vt 0.729167 0.833333 +vt 0.729167 0.916667 +vt 0.729167 1.000000 +vt 0.729167 0.000000 +vt 0.729167 0.083333 +vt 0.729167 0.166667 +vt 0.729167 0.250000 +vt 0.729167 0.333333 +vt 0.729167 0.416667 +vt 0.750000 0.500000 +vt 0.750000 0.583333 +vt 0.750000 0.666667 +vt 0.750000 0.750000 +vt 0.750000 0.833333 +vt 0.750000 0.916667 +vt 0.750000 1.000000 +vt 0.750000 0.000000 +vt 0.750000 0.083333 +vt 0.750000 0.166667 +vt 0.750000 0.250000 +vt 0.750000 0.333333 +vt 0.750000 0.416667 +vt 0.770833 0.500000 +vt 0.770833 0.583333 +vt 0.770833 0.666667 +vt 0.770833 0.750000 +vt 0.770833 0.833333 +vt 0.770833 0.916667 +vt 0.770833 1.000000 +vt 0.770833 0.000000 +vt 0.770833 0.083333 +vt 0.770833 0.166667 +vt 0.770833 0.250000 +vt 0.770833 0.333333 +vt 0.770833 0.416667 +vt 0.791667 0.500000 +vt 0.791667 0.583333 +vt 0.791667 0.666667 +vt 0.791667 0.750000 +vt 0.791667 0.833333 +vt 0.791667 0.916667 +vt 0.791667 1.000000 +vt 0.791667 0.000000 +vt 0.791667 0.083333 +vt 0.791667 0.166667 +vt 0.791667 0.250000 +vt 0.791667 0.333333 +vt 0.791667 0.416667 +vt 0.812500 0.500000 +vt 0.812500 0.583333 +vt 0.812500 0.666667 +vt 0.812500 0.750000 +vt 0.812500 0.833333 +vt 0.812500 0.916667 +vt 0.812500 1.000000 +vt 0.812500 0.000000 +vt 0.812500 0.083333 +vt 0.812500 0.166667 +vt 0.812500 0.250000 +vt 0.812500 0.333333 +vt 0.812500 0.416667 +vt 0.833333 0.500000 +vt 0.833333 0.583333 +vt 0.833333 0.666667 +vt 0.833333 0.750000 +vt 0.833333 0.833333 +vt 0.833333 0.916667 +vt 0.833333 1.000000 +vt 0.833333 0.000000 +vt 0.833333 0.083333 +vt 0.833333 0.166667 +vt 0.833333 0.250000 +vt 0.833333 0.333333 +vt 0.833333 0.416667 +vt 0.854167 0.500000 +vt 0.854167 0.583333 +vt 0.854167 0.666667 +vt 0.854167 0.750000 +vt 0.854167 0.833333 +vt 0.854167 0.916667 +vt 0.854167 1.000000 +vt 0.854167 0.000000 +vt 0.854167 0.083333 +vt 0.854167 0.166667 +vt 0.854167 0.250000 +vt 0.854167 0.333333 +vt 0.854167 0.416667 +vt 0.875000 0.500000 +vt 0.875000 0.583333 +vt 0.875000 0.666667 +vt 0.875000 0.750000 +vt 0.875000 0.833333 +vt 0.875000 0.916667 +vt 0.875000 1.000000 +vt 0.875000 0.000000 +vt 0.875000 0.083333 +vt 0.875000 0.166667 +vt 0.875000 0.250000 +vt 0.875000 0.333333 +vt 0.875000 0.416667 +vt 0.895833 0.500000 +vt 0.895833 0.583333 +vt 0.895833 0.666667 +vt 0.895833 0.750000 +vt 0.895833 0.833333 +vt 0.895833 0.916667 +vt 0.895833 1.000000 +vt 0.895833 0.000000 +vt 0.895833 0.083333 +vt 0.895833 0.166667 +vt 0.895833 0.250000 +vt 0.895833 0.333333 +vt 0.895833 0.416667 +vt 0.916667 0.500000 +vt 0.916667 0.583333 +vt 0.916667 0.666667 +vt 0.916667 0.750000 +vt 0.916667 0.833333 +vt 0.916667 0.916667 +vt 0.916667 1.000000 +vt 0.916667 0.000000 +vt 0.916667 0.083333 +vt 0.916667 0.166667 +vt 0.916667 0.250000 +vt 0.916667 0.333333 +vt 0.916667 0.416667 +vt 0.937500 0.500000 +vt 0.937500 0.583333 +vt 0.937500 0.666667 +vt 0.937500 0.750000 +vt 0.937500 0.833333 +vt 0.937500 0.916667 +vt 0.937500 1.000000 +vt 0.937500 0.000000 +vt 0.937500 0.083333 +vt 0.937500 0.166667 +vt 0.937500 0.250000 +vt 0.937500 0.333333 +vt 0.937500 0.416667 +vt 0.958333 0.500000 +vt 0.958333 0.583333 +vt 0.958333 0.666667 +vt 0.958333 0.750000 +vt 0.958333 0.833333 +vt 0.958333 0.916667 +vt 0.958333 1.000000 +vt 0.958333 0.000000 +vt 0.958333 0.083333 +vt 0.958333 0.166667 +vt 0.958333 0.250000 +vt 0.958333 0.333333 +vt 0.958333 0.416667 +vt 0.979167 0.500000 +vt 0.979167 0.583333 +vt 0.979167 0.666667 +vt 0.979167 0.750000 +vt 0.979167 0.833333 +vt 0.979167 0.916667 +vt 0.979167 1.000000 +vt 0.979167 0.000000 +vt 0.979167 0.083333 +vt 0.979167 0.166667 +vt 0.979167 0.250000 +vt 0.979167 0.333333 +vt 0.979167 0.416667 +vt 1.000000 0.500000 +vt 1.000000 0.583333 +vt 1.000000 0.666667 +vt 1.000000 0.750000 +vt 1.000000 0.833333 +vt 1.000000 0.916667 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.083333 +vt 1.000000 0.166667 +vt 1.000000 0.250000 +vt 1.000000 0.333333 +vt 1.000000 0.416667 +vt 0.000000 0.500000 +vt 0.020833 0.500000 +vt 0.020833 0.583333 +vt 0.000000 0.583333 +vt 0.020833 0.666667 +vt 0.000000 0.666667 +vt 0.020833 0.750000 +vt 0.000000 0.750000 +vt 0.020833 0.833333 +vt 0.000000 0.833333 +vt 0.020833 0.916667 +vt 0.000000 0.916667 +vt 0.020833 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.020833 0.000000 +vt 0.020833 0.083333 +vt 0.000000 0.083333 +vt 0.020833 0.166667 +vt 0.000000 0.166667 +vt 0.020833 0.250000 +vt 0.000000 0.250000 +vt 0.020833 0.333333 +vt 0.000000 0.333333 +vt 0.020833 0.416667 +vt 0.000000 0.416667 +vt 0.041667 0.500000 +vt 0.041667 0.583333 +vt 0.041667 0.666667 +vt 0.041667 0.750000 +vt 0.041667 0.833333 +vt 0.041667 0.916667 +vt 0.041667 1.000000 +vt 0.041667 0.000000 +vt 0.041667 0.083333 +vt 0.041667 0.166667 +vt 0.041667 0.250000 +vt 0.041667 0.333333 +vt 0.041667 0.416667 +vt 0.062500 0.500000 +vt 0.062500 0.583333 +vt 0.062500 0.666667 +vt 0.062500 0.750000 +vt 0.062500 0.833333 +vt 0.062500 0.916667 +vt 0.062500 1.000000 +vt 0.062500 0.000000 +vt 0.062500 0.083333 +vt 0.062500 0.166667 +vt 0.062500 0.250000 +vt 0.062500 0.333333 +vt 0.062500 0.416667 +vt 0.083333 0.500000 +vt 0.083333 0.583333 +vt 0.083333 0.666667 +vt 0.083333 0.750000 +vt 0.083333 0.833333 +vt 0.083333 0.916667 +vt 0.083333 1.000000 +vt 0.083333 0.000000 +vt 0.083333 0.083333 +vt 0.083333 0.166667 +vt 0.083333 0.250000 +vt 0.083333 0.333333 +vt 0.083333 0.416667 +vt 0.104167 0.500000 +vt 0.104167 0.583333 +vt 0.104167 0.666667 +vt 0.104167 0.750000 +vt 0.104167 0.833333 +vt 0.104167 0.916667 +vt 0.104167 1.000000 +vt 0.104167 0.000000 +vt 0.104167 0.083333 +vt 0.104167 0.166667 +vt 0.104167 0.250000 +vt 0.104167 0.333333 +vt 0.104167 0.416667 +vt 0.125000 0.500000 +vt 0.125000 0.583333 +vt 0.125000 0.666667 +vt 0.125000 0.750000 +vt 0.125000 0.833333 +vt 0.125000 0.916667 +vt 0.125000 1.000000 +vt 0.125000 0.000000 +vt 0.125000 0.083333 +vt 0.125000 0.166667 +vt 0.125000 0.250000 +vt 0.125000 0.333333 +vt 0.125000 0.416667 +vt 0.145833 0.500000 +vt 0.145833 0.583333 +vt 0.145833 0.666667 +vt 0.145833 0.750000 +vt 0.145833 0.833333 +vt 0.145833 0.916667 +vt 0.145833 1.000000 +vt 0.145833 0.000000 +vt 0.145833 0.083333 +vt 0.145833 0.166667 +vt 0.145833 0.250000 +vt 0.145833 0.333333 +vt 0.145833 0.416667 +vt 0.166667 0.500000 +vt 0.166667 0.583333 +vt 0.166667 0.666667 +vt 0.166667 0.750000 +vt 0.166667 0.833333 +vt 0.166667 0.916667 +vt 0.166667 1.000000 +vt 0.166667 0.000000 +vt 0.166667 0.083333 +vt 0.166667 0.166667 +vt 0.166667 0.250000 +vt 0.166667 0.333333 +vt 0.166667 0.416667 +vt 0.187500 0.500000 +vt 0.187500 0.583333 +vt 0.187500 0.666667 +vt 0.187500 0.750000 +vt 0.187500 0.833333 +vt 0.187500 0.916667 +vt 0.187500 1.000000 +vt 0.187500 0.000000 +vt 0.187500 0.083333 +vt 0.187500 0.166667 +vt 0.187500 0.250000 +vt 0.187500 0.333333 +vt 0.187500 0.416667 +vt 0.208333 0.500000 +vt 0.208333 0.583333 +vt 0.208333 0.666667 +vt 0.208333 0.750000 +vt 0.208333 0.833333 +vt 0.208333 0.916667 +vt 0.208333 1.000000 +vt 0.208333 0.000000 +vt 0.208333 0.083333 +vt 0.208333 0.166667 +vt 0.208333 0.250000 +vt 0.208333 0.333333 +vt 0.208333 0.416667 +vt 0.229167 0.500000 +vt 0.229167 0.583333 +vt 0.229167 0.666667 +vt 0.229167 0.750000 +vt 0.229167 0.833333 +vt 0.229167 0.916667 +vt 0.229167 1.000000 +vt 0.229167 0.000000 +vt 0.229167 0.083333 +vt 0.229167 0.166667 +vt 0.229167 0.250000 +vt 0.229167 0.333333 +vt 0.229167 0.416667 +vt 0.250000 0.500000 +vt 0.250000 0.583333 +vt 0.250000 0.666667 +vt 0.250000 0.750000 +vt 0.250000 0.833333 +vt 0.250000 0.916667 +vt 0.250000 1.000000 +vt 0.250000 0.000000 +vt 0.250000 0.083333 +vt 0.250000 0.166667 +vt 0.250000 0.250000 +vt 0.250000 0.333333 +vt 0.250000 0.416667 +vt 0.270833 0.500000 +vt 0.270833 0.583333 +vt 0.270833 0.666667 +vt 0.270833 0.750000 +vt 0.270833 0.833333 +vt 0.270833 0.916667 +vt 0.270833 1.000000 +vt 0.270833 0.000000 +vt 0.270833 0.083333 +vt 0.270833 0.166667 +vt 0.270833 0.250000 +vt 0.270833 0.333333 +vt 0.270833 0.416667 +vt 0.291667 0.500000 +vt 0.291667 0.583333 +vt 0.291667 0.666667 +vt 0.291667 0.750000 +vt 0.291667 0.833333 +vt 0.291667 0.916667 +vt 0.291667 1.000000 +vt 0.291667 0.000000 +vt 0.291667 0.083333 +vt 0.291667 0.166667 +vt 0.291667 0.250000 +vt 0.291667 0.333333 +vt 0.291667 0.416667 +vt 0.312500 0.500000 +vt 0.312500 0.583333 +vt 0.312500 0.666667 +vt 0.312500 0.750000 +vt 0.312500 0.833333 +vt 0.312500 0.916667 +vt 0.312500 1.000000 +vt 0.312500 0.000000 +vt 0.312500 0.083333 +vt 0.312500 0.166667 +vt 0.312500 0.250000 +vt 0.312500 0.333333 +vt 0.312500 0.416667 +vt 0.333333 0.500000 +vt 0.333333 0.583333 +vt 0.333333 0.666667 +vt 0.333333 0.750000 +vt 0.333333 0.833333 +vt 0.333333 0.916667 +vt 0.333333 1.000000 +vt 0.333333 0.000000 +vt 0.333333 0.083333 +vt 0.333333 0.166667 +vt 0.333333 0.250000 +vt 0.333333 0.333333 +vt 0.333333 0.416667 +vt 0.354167 0.500000 +vt 0.354167 0.583333 +vt 0.354167 0.666667 +vt 0.354167 0.750000 +vt 0.354167 0.833333 +vt 0.354167 0.916667 +vt 0.354167 1.000000 +vt 0.354167 0.000000 +vt 0.354167 0.083333 +vt 0.354167 0.166667 +vt 0.354167 0.250000 +vt 0.354167 0.333333 +vt 0.354167 0.416667 +vt 0.375000 0.500000 +vt 0.375000 0.583333 +vt 0.375000 0.666667 +vt 0.375000 0.750000 +vt 0.375000 0.833333 +vt 0.375000 0.916667 +vt 0.375000 1.000000 +vt 0.375000 0.000000 +vt 0.375000 0.083333 +vt 0.375000 0.166667 +vt 0.375000 0.250000 +vt 0.375000 0.333333 +vt 0.375000 0.416667 +vt 0.395833 0.500000 +vt 0.395833 0.583333 +vt 0.395833 0.666667 +vt 0.395833 0.750000 +vt 0.395833 0.833333 +vt 0.395833 0.916667 +vt 0.395833 1.000000 +vt 0.395833 0.000000 +vt 0.395833 0.083333 +vt 0.395833 0.166667 +vt 0.395833 0.250000 +vt 0.395833 0.333333 +vt 0.395833 0.416667 +vt 0.416667 0.500000 +vt 0.416667 0.583333 +vt 0.416667 0.666667 +vt 0.416667 0.750000 +vt 0.416667 0.833333 +vt 0.416667 0.916667 +vt 0.416667 1.000000 +vt 0.416667 0.000000 +vt 0.416667 0.083333 +vt 0.416667 0.166667 +vt 0.416667 0.250000 +vt 0.416667 0.333333 +vt 0.416667 0.416667 +vt 0.437500 0.500000 +vt 0.437500 0.583333 +vt 0.437500 0.666667 +vt 0.437500 0.750000 +vt 0.437500 0.833333 +vt 0.437500 0.916667 +vt 0.437500 1.000000 +vt 0.437500 0.000000 +vt 0.437500 0.083333 +vt 0.437500 0.166667 +vt 0.437500 0.250000 +vt 0.437500 0.333333 +vt 0.437500 0.416667 +vt 0.458333 0.500000 +vt 0.458333 0.583333 +vt 0.458333 0.666667 +vt 0.458333 0.750000 +vt 0.458333 0.833333 +vt 0.458333 0.916667 +vt 0.458333 1.000000 +vt 0.458333 0.000000 +vt 0.458333 0.083333 +vt 0.458333 0.166667 +vt 0.458333 0.250000 +vt 0.458333 0.333333 +vt 0.458333 0.416667 +vt 0.479167 0.500000 +vt 0.479167 0.583333 +vt 0.479167 0.666667 +vt 0.479167 0.750000 +vt 0.479167 0.833333 +vt 0.479167 0.916667 +vt 0.479167 1.000000 +vt 0.479167 0.000000 +vt 0.479167 0.083333 +vt 0.479167 0.166667 +vt 0.479167 0.250000 +vt 0.479167 0.333333 +vt 0.479167 0.416667 +vn 0.9640 0.2583 -0.0632 +vn 0.7063 0.7063 -0.0463 +vn 0.2588 0.9658 -0.0170 +vn -0.2588 0.9658 0.0170 +vn -0.7063 0.7063 0.0463 +vn -0.9640 0.2583 0.0632 +vn -0.9640 -0.2583 0.0632 +vn -0.7063 -0.7063 0.0463 +vn -0.2588 -0.9658 0.0170 +vn 0.2588 -0.9658 -0.0170 +vn 0.7063 -0.7063 -0.0463 +vn 0.9640 -0.2583 -0.0632 +vn 0.9475 0.2583 -0.1885 +vn 0.6943 0.7063 -0.1381 +vn 0.2544 0.9658 -0.0506 +vn -0.2544 0.9658 0.0506 +vn -0.6943 0.7063 0.1381 +vn -0.9475 0.2583 0.1885 +vn -0.9475 -0.2583 0.1885 +vn -0.6943 -0.7063 0.1381 +vn -0.2544 -0.9658 0.0506 +vn 0.2544 -0.9658 -0.0506 +vn 0.6943 -0.7063 -0.1381 +vn 0.9475 -0.2583 -0.1885 +vn 0.9148 0.2583 -0.3105 +vn 0.6703 0.7063 -0.2275 +vn 0.2456 0.9658 -0.0834 +vn -0.2456 0.9658 0.0834 +vn -0.6703 0.7063 0.2275 +vn -0.9148 0.2583 0.3105 +vn -0.9148 -0.2583 0.3105 +vn -0.6703 -0.7063 0.2275 +vn -0.2456 -0.9658 0.0834 +vn 0.2456 -0.9658 -0.0834 +vn 0.6703 -0.7063 -0.2275 +vn 0.9148 -0.2583 -0.3105 +vn 0.8664 0.2583 -0.4273 +vn 0.6349 0.7063 -0.3131 +vn 0.2326 0.9658 -0.1147 +vn -0.2326 0.9658 0.1147 +vn -0.6349 0.7063 0.3131 +vn -0.8664 0.2583 0.4273 +vn -0.8664 -0.2583 0.4273 +vn -0.6349 -0.7063 0.3131 +vn -0.2326 -0.9658 0.1147 +vn 0.2326 -0.9658 -0.1147 +vn 0.6349 -0.7063 -0.3131 +vn 0.8664 -0.2583 -0.4273 +vn 0.8033 0.2583 -0.5367 +vn 0.5886 0.7063 -0.3933 +vn 0.2156 0.9658 -0.1441 +vn -0.2156 0.9658 0.1441 +vn -0.5886 0.7063 0.3933 +vn -0.8033 0.2583 0.5367 +vn -0.8033 -0.2583 0.5367 +vn -0.5886 -0.7063 0.3933 +vn -0.2156 -0.9658 0.1441 +vn 0.2156 -0.9658 -0.1441 +vn 0.5886 -0.7063 -0.3933 +vn 0.8033 -0.2583 -0.5367 +vn 0.7263 0.2583 -0.6370 +vn 0.5322 0.7063 -0.4667 +vn 0.1950 0.9658 -0.1710 +vn -0.1950 0.9658 0.1710 +vn -0.5322 0.7063 0.4667 +vn -0.7263 0.2583 0.6370 +vn -0.7263 -0.2583 0.6370 +vn -0.5322 -0.7063 0.4667 +vn -0.1950 -0.9658 0.1710 +vn 0.1950 -0.9658 -0.1710 +vn 0.5322 -0.7063 -0.4667 +vn 0.7263 -0.2583 -0.6370 +vn 0.6370 0.2583 -0.7263 +vn 0.4667 0.7063 -0.5322 +vn 0.1710 0.9658 -0.1950 +vn -0.1710 0.9658 0.1950 +vn -0.4667 0.7063 0.5322 +vn -0.6370 0.2583 0.7263 +vn -0.6370 -0.2583 0.7263 +vn -0.4667 -0.7063 0.5322 +vn -0.1710 -0.9658 0.1950 +vn 0.1710 -0.9658 -0.1950 +vn 0.4667 -0.7063 -0.5322 +vn 0.6370 -0.2583 -0.7263 +vn 0.5367 0.2583 -0.8033 +vn 0.3933 0.7063 -0.5886 +vn 0.1441 0.9658 -0.2156 +vn -0.1441 0.9658 0.2156 +vn -0.3933 0.7063 0.5886 +vn -0.5367 0.2583 0.8033 +vn -0.5367 -0.2583 0.8033 +vn -0.3933 -0.7063 0.5886 +vn -0.1441 -0.9658 0.2156 +vn 0.1441 -0.9658 -0.2156 +vn 0.3933 -0.7063 -0.5886 +vn 0.5367 -0.2583 -0.8033 +vn 0.4273 0.2583 -0.8664 +vn 0.3131 0.7063 -0.6349 +vn 0.1147 0.9658 -0.2326 +vn -0.1147 0.9658 0.2326 +vn -0.3131 0.7063 0.6349 +vn -0.4273 0.2583 0.8664 +vn -0.4273 -0.2583 0.8664 +vn -0.3131 -0.7063 0.6349 +vn -0.1147 -0.9658 0.2326 +vn 0.1147 -0.9658 -0.2326 +vn 0.3131 -0.7063 -0.6349 +vn 0.4273 -0.2583 -0.8664 +vn 0.3105 0.2583 -0.9148 +vn 0.2275 0.7063 -0.6703 +vn 0.0834 0.9658 -0.2456 +vn -0.0834 0.9658 0.2456 +vn -0.2275 0.7063 0.6703 +vn -0.3105 0.2583 0.9148 +vn -0.3105 -0.2583 0.9148 +vn -0.2275 -0.7063 0.6703 +vn -0.0834 -0.9658 0.2456 +vn 0.0834 -0.9658 -0.2456 +vn 0.2275 -0.7063 -0.6703 +vn 0.3105 -0.2583 -0.9148 +vn 0.1885 0.2583 -0.9475 +vn 0.1381 0.7063 -0.6943 +vn 0.0506 0.9658 -0.2544 +vn -0.0506 0.9658 0.2544 +vn -0.1381 0.7063 0.6943 +vn -0.1885 0.2583 0.9475 +vn -0.1885 -0.2583 0.9475 +vn -0.1381 -0.7063 0.6943 +vn -0.0506 -0.9658 0.2544 +vn 0.0506 -0.9658 -0.2544 +vn 0.1381 -0.7063 -0.6943 +vn 0.1885 -0.2583 -0.9475 +vn 0.0632 0.2583 -0.9640 +vn 0.0463 0.7063 -0.7063 +vn 0.0170 0.9658 -0.2588 +vn -0.0170 0.9658 0.2588 +vn -0.0463 0.7063 0.7063 +vn -0.0632 0.2583 0.9640 +vn -0.0632 -0.2583 0.9640 +vn -0.0463 -0.7063 0.7063 +vn -0.0170 -0.9658 0.2588 +vn 0.0170 -0.9658 -0.2588 +vn 0.0463 -0.7063 -0.7063 +vn 0.0632 -0.2583 -0.9640 +vn -0.0632 0.2583 -0.9640 +vn -0.0463 0.7063 -0.7063 +vn -0.0170 0.9658 -0.2588 +vn 0.0170 0.9658 0.2588 +vn 0.0463 0.7063 0.7063 +vn 0.0632 0.2583 0.9640 +vn 0.0632 -0.2583 0.9640 +vn 0.0463 -0.7063 0.7063 +vn 0.0170 -0.9658 0.2588 +vn -0.0170 -0.9658 -0.2588 +vn -0.0463 -0.7063 -0.7063 +vn -0.0632 -0.2583 -0.9640 +vn -0.1885 0.2583 -0.9475 +vn -0.1381 0.7063 -0.6943 +vn -0.0506 0.9658 -0.2544 +vn 0.0506 0.9658 0.2544 +vn 0.1381 0.7063 0.6943 +vn 0.1885 0.2583 0.9475 +vn 0.1885 -0.2583 0.9475 +vn 0.1381 -0.7063 0.6943 +vn 0.0506 -0.9658 0.2544 +vn -0.0506 -0.9658 -0.2544 +vn -0.1381 -0.7063 -0.6943 +vn -0.1885 -0.2583 -0.9475 +vn -0.3105 0.2583 -0.9148 +vn -0.2275 0.7063 -0.6703 +vn -0.0834 0.9658 -0.2456 +vn 0.0834 0.9658 0.2456 +vn 0.2275 0.7063 0.6703 +vn 0.3105 0.2583 0.9148 +vn 0.3105 -0.2583 0.9148 +vn 0.2275 -0.7063 0.6703 +vn 0.0834 -0.9658 0.2456 +vn -0.0834 -0.9658 -0.2456 +vn -0.2275 -0.7063 -0.6703 +vn -0.3105 -0.2583 -0.9148 +vn -0.4273 0.2583 -0.8664 +vn -0.3131 0.7063 -0.6349 +vn -0.1147 0.9658 -0.2326 +vn 0.1147 0.9658 0.2326 +vn 0.3131 0.7063 0.6349 +vn 0.4273 0.2583 0.8664 +vn 0.4273 -0.2583 0.8664 +vn 0.3131 -0.7063 0.6349 +vn 0.1147 -0.9658 0.2326 +vn -0.1147 -0.9658 -0.2326 +vn -0.3131 -0.7063 -0.6349 +vn -0.4273 -0.2583 -0.8664 +vn -0.5367 0.2583 -0.8033 +vn -0.3933 0.7063 -0.5886 +vn -0.1441 0.9658 -0.2156 +vn 0.1441 0.9658 0.2156 +vn 0.3933 0.7063 0.5886 +vn 0.5367 0.2583 0.8033 +vn 0.5367 -0.2583 0.8033 +vn 0.3933 -0.7063 0.5886 +vn 0.1441 -0.9658 0.2156 +vn -0.1441 -0.9658 -0.2156 +vn -0.3933 -0.7063 -0.5886 +vn -0.5367 -0.2583 -0.8033 +vn -0.6370 0.2583 -0.7263 +vn -0.4667 0.7063 -0.5322 +vn -0.1710 0.9658 -0.1950 +vn 0.1710 0.9658 0.1950 +vn 0.4667 0.7063 0.5322 +vn 0.6370 0.2583 0.7263 +vn 0.6370 -0.2583 0.7263 +vn 0.4667 -0.7063 0.5322 +vn 0.1710 -0.9658 0.1950 +vn -0.1710 -0.9658 -0.1950 +vn -0.4667 -0.7063 -0.5322 +vn -0.6370 -0.2583 -0.7263 +vn -0.7263 0.2583 -0.6370 +vn -0.5322 0.7063 -0.4667 +vn -0.1950 0.9658 -0.1710 +vn 0.1950 0.9658 0.1710 +vn 0.5322 0.7063 0.4667 +vn 0.7263 0.2583 0.6370 +vn 0.7263 -0.2583 0.6370 +vn 0.5322 -0.7063 0.4667 +vn 0.1950 -0.9658 0.1710 +vn -0.1950 -0.9658 -0.1710 +vn -0.5322 -0.7063 -0.4667 +vn -0.7263 -0.2583 -0.6370 +vn -0.8033 0.2583 -0.5367 +vn -0.5886 0.7063 -0.3933 +vn -0.2156 0.9658 -0.1441 +vn 0.2156 0.9658 0.1441 +vn 0.5886 0.7063 0.3933 +vn 0.8033 0.2583 0.5367 +vn 0.8033 -0.2583 0.5367 +vn 0.5886 -0.7063 0.3933 +vn 0.2156 -0.9658 0.1441 +vn -0.2156 -0.9658 -0.1441 +vn -0.5886 -0.7063 -0.3933 +vn -0.8033 -0.2583 -0.5367 +vn -0.8664 0.2583 -0.4273 +vn -0.6349 0.7063 -0.3131 +vn -0.2326 0.9658 -0.1147 +vn 0.2326 0.9658 0.1147 +vn 0.6349 0.7063 0.3131 +vn 0.8664 0.2583 0.4273 +vn 0.8664 -0.2583 0.4273 +vn 0.6349 -0.7063 0.3131 +vn 0.2326 -0.9658 0.1147 +vn -0.2326 -0.9658 -0.1147 +vn -0.6349 -0.7063 -0.3131 +vn -0.8664 -0.2583 -0.4273 +vn -0.9148 0.2583 -0.3105 +vn -0.6703 0.7063 -0.2275 +vn -0.2456 0.9658 -0.0834 +vn 0.2456 0.9658 0.0834 +vn 0.6703 0.7063 0.2275 +vn 0.9148 0.2583 0.3105 +vn 0.9148 -0.2583 0.3105 +vn 0.6703 -0.7063 0.2275 +vn 0.2456 -0.9658 0.0834 +vn -0.2456 -0.9658 -0.0834 +vn -0.6703 -0.7063 -0.2275 +vn -0.9148 -0.2583 -0.3105 +vn -0.9475 0.2583 -0.1885 +vn -0.6943 0.7063 -0.1381 +vn -0.2544 0.9658 -0.0506 +vn 0.2544 0.9658 0.0506 +vn 0.6943 0.7063 0.1381 +vn 0.9475 0.2583 0.1885 +vn 0.9475 -0.2583 0.1885 +vn 0.6943 -0.7063 0.1381 +vn 0.2544 -0.9658 0.0506 +vn -0.2544 -0.9658 -0.0506 +vn -0.6943 -0.7063 -0.1381 +vn -0.9475 -0.2583 -0.1885 +vn -0.9640 0.2583 -0.0632 +vn -0.7063 0.7063 -0.0463 +vn -0.2588 0.9658 -0.0170 +vn 0.2588 0.9658 0.0170 +vn 0.7063 0.7063 0.0463 +vn 0.9640 0.2583 0.0632 +vn 0.9640 -0.2583 0.0632 +vn 0.7063 -0.7063 0.0463 +vn 0.2588 -0.9658 0.0170 +vn -0.2588 -0.9658 -0.0170 +vn -0.7063 -0.7063 -0.0463 +vn -0.9640 -0.2583 -0.0632 +usemtl Material +s off +f 1/1/1 13/2/1 14/3/1 2/4/1 +f 2/4/2 14/3/2 15/5/2 3/6/2 +f 3/6/3 15/5/3 16/7/3 4/8/3 +f 4/8/4 16/7/4 17/9/4 5/10/4 +f 5/10/5 17/9/5 18/11/5 6/12/5 +f 6/12/6 18/11/6 19/13/6 7/14/6 +f 7/15/7 19/16/7 20/17/7 8/18/7 +f 8/18/8 20/17/8 21/19/8 9/20/8 +f 9/20/9 21/19/9 22/21/9 10/22/9 +f 10/22/10 22/21/10 23/23/10 11/24/10 +f 11/24/11 23/23/11 24/25/11 12/26/11 +f 12/26/12 24/25/12 13/2/12 1/1/12 +f 13/2/13 25/27/13 26/28/13 14/3/13 +f 14/3/14 26/28/14 27/29/14 15/5/14 +f 15/5/15 27/29/15 28/30/15 16/7/15 +f 16/7/16 28/30/16 29/31/16 17/9/16 +f 17/9/17 29/31/17 30/32/17 18/11/17 +f 18/11/18 30/32/18 31/33/18 19/13/18 +f 19/16/19 31/34/19 32/35/19 20/17/19 +f 20/17/20 32/35/20 33/36/20 21/19/20 +f 21/19/21 33/36/21 34/37/21 22/21/21 +f 22/21/22 34/37/22 35/38/22 23/23/22 +f 23/23/23 35/38/23 36/39/23 24/25/23 +f 24/25/24 36/39/24 25/27/24 13/2/24 +f 25/27/25 37/40/25 38/41/25 26/28/25 +f 26/28/26 38/41/26 39/42/26 27/29/26 +f 27/29/27 39/42/27 40/43/27 28/30/27 +f 28/30/28 40/43/28 41/44/28 29/31/28 +f 29/31/29 41/44/29 42/45/29 30/32/29 +f 30/32/30 42/45/30 43/46/30 31/33/30 +f 31/34/31 43/47/31 44/48/31 32/35/31 +f 32/35/32 44/48/32 45/49/32 33/36/32 +f 33/36/33 45/49/33 46/50/33 34/37/33 +f 34/37/34 46/50/34 47/51/34 35/38/34 +f 35/38/35 47/51/35 48/52/35 36/39/35 +f 36/39/36 48/52/36 37/40/36 25/27/36 +f 37/40/37 49/53/37 50/54/37 38/41/37 +f 38/41/38 50/54/38 51/55/38 39/42/38 +f 39/42/39 51/55/39 52/56/39 40/43/39 +f 40/43/40 52/56/40 53/57/40 41/44/40 +f 41/44/41 53/57/41 54/58/41 42/45/41 +f 42/45/42 54/58/42 55/59/42 43/46/42 +f 43/47/43 55/60/43 56/61/43 44/48/43 +f 44/48/44 56/61/44 57/62/44 45/49/44 +f 45/49/45 57/62/45 58/63/45 46/50/45 +f 46/50/46 58/63/46 59/64/46 47/51/46 +f 47/51/47 59/64/47 60/65/47 48/52/47 +f 48/52/48 60/65/48 49/53/48 37/40/48 +f 49/53/49 61/66/49 62/67/49 50/54/49 +f 50/54/50 62/67/50 63/68/50 51/55/50 +f 51/55/51 63/68/51 64/69/51 52/56/51 +f 52/56/52 64/69/52 65/70/52 53/57/52 +f 53/57/53 65/70/53 66/71/53 54/58/53 +f 54/58/54 66/71/54 67/72/54 55/59/54 +f 55/60/55 67/73/55 68/74/55 56/61/55 +f 56/61/56 68/74/56 69/75/56 57/62/56 +f 57/62/57 69/75/57 70/76/57 58/63/57 +f 58/63/58 70/76/58 71/77/58 59/64/58 +f 59/64/59 71/77/59 72/78/59 60/65/59 +f 60/65/60 72/78/60 61/66/60 49/53/60 +f 61/66/61 73/79/61 74/80/61 62/67/61 +f 62/67/62 74/80/62 75/81/62 63/68/62 +f 63/68/63 75/81/63 76/82/63 64/69/63 +f 64/69/64 76/82/64 77/83/64 65/70/64 +f 65/70/65 77/83/65 78/84/65 66/71/65 +f 66/71/66 78/84/66 79/85/66 67/72/66 +f 67/73/67 79/86/67 80/87/67 68/74/67 +f 68/74/68 80/87/68 81/88/68 69/75/68 +f 69/75/69 81/88/69 82/89/69 70/76/69 +f 70/76/70 82/89/70 83/90/70 71/77/70 +f 71/77/71 83/90/71 84/91/71 72/78/71 +f 72/78/72 84/91/72 73/79/72 61/66/72 +f 73/79/73 85/92/73 86/93/73 74/80/73 +f 74/80/74 86/93/74 87/94/74 75/81/74 +f 75/81/75 87/94/75 88/95/75 76/82/75 +f 76/82/76 88/95/76 89/96/76 77/83/76 +f 77/83/77 89/96/77 90/97/77 78/84/77 +f 78/84/78 90/97/78 91/98/78 79/85/78 +f 79/86/79 91/99/79 92/100/79 80/87/79 +f 80/87/80 92/100/80 93/101/80 81/88/80 +f 81/88/81 93/101/81 94/102/81 82/89/81 +f 82/89/82 94/102/82 95/103/82 83/90/82 +f 83/90/83 95/103/83 96/104/83 84/91/83 +f 84/91/84 96/104/84 85/92/84 73/79/84 +f 85/92/85 97/105/85 98/106/85 86/93/85 +f 86/93/86 98/106/86 99/107/86 87/94/86 +f 87/94/87 99/107/87 100/108/87 88/95/87 +f 88/95/88 100/108/88 101/109/88 89/96/88 +f 89/96/89 101/109/89 102/110/89 90/97/89 +f 90/97/90 102/110/90 103/111/90 91/98/90 +f 91/99/91 103/112/91 104/113/91 92/100/91 +f 92/100/92 104/113/92 105/114/92 93/101/92 +f 93/101/93 105/114/93 106/115/93 94/102/93 +f 94/102/94 106/115/94 107/116/94 95/103/94 +f 95/103/95 107/116/95 108/117/95 96/104/95 +f 96/104/96 108/117/96 97/105/96 85/92/96 +f 97/105/97 109/118/97 110/119/97 98/106/97 +f 98/106/98 110/119/98 111/120/98 99/107/98 +f 99/107/99 111/120/99 112/121/99 100/108/99 +f 100/108/100 112/121/100 113/122/100 101/109/100 +f 101/109/101 113/122/101 114/123/101 102/110/101 +f 102/110/102 114/123/102 115/124/102 103/111/102 +f 103/112/103 115/125/103 116/126/103 104/113/103 +f 104/113/104 116/126/104 117/127/104 105/114/104 +f 105/114/105 117/127/105 118/128/105 106/115/105 +f 106/115/106 118/128/106 119/129/106 107/116/106 +f 107/116/107 119/129/107 120/130/107 108/117/107 +f 108/117/108 120/130/108 109/118/108 97/105/108 +f 109/118/109 121/131/109 122/132/109 110/119/109 +f 110/119/110 122/132/110 123/133/110 111/120/110 +f 111/120/111 123/133/111 124/134/111 112/121/111 +f 112/121/112 124/134/112 125/135/112 113/122/112 +f 113/122/113 125/135/113 126/136/113 114/123/113 +f 114/123/114 126/136/114 127/137/114 115/124/114 +f 115/125/115 127/138/115 128/139/115 116/126/115 +f 116/126/116 128/139/116 129/140/116 117/127/116 +f 117/127/117 129/140/117 130/141/117 118/128/117 +f 118/128/118 130/141/118 131/142/118 119/129/118 +f 119/129/119 131/142/119 132/143/119 120/130/119 +f 120/130/120 132/143/120 121/131/120 109/118/120 +f 121/131/121 133/144/121 134/145/121 122/132/121 +f 122/132/122 134/145/122 135/146/122 123/133/122 +f 123/133/123 135/146/123 136/147/123 124/134/123 +f 124/134/124 136/147/124 137/148/124 125/135/124 +f 125/135/125 137/148/125 138/149/125 126/136/125 +f 126/136/126 138/149/126 139/150/126 127/137/126 +f 127/138/127 139/151/127 140/152/127 128/139/127 +f 128/139/128 140/152/128 141/153/128 129/140/128 +f 129/140/129 141/153/129 142/154/129 130/141/129 +f 130/141/130 142/154/130 143/155/130 131/142/130 +f 131/142/131 143/155/131 144/156/131 132/143/131 +f 132/143/132 144/156/132 133/144/132 121/131/132 +f 133/144/133 145/157/133 146/158/133 134/145/133 +f 134/145/134 146/158/134 147/159/134 135/146/134 +f 135/146/135 147/159/135 148/160/135 136/147/135 +f 136/147/136 148/160/136 149/161/136 137/148/136 +f 137/148/137 149/161/137 150/162/137 138/149/137 +f 138/149/138 150/162/138 151/163/138 139/150/138 +f 139/151/139 151/164/139 152/165/139 140/152/139 +f 140/152/140 152/165/140 153/166/140 141/153/140 +f 141/153/141 153/166/141 154/167/141 142/154/141 +f 142/154/142 154/167/142 155/168/142 143/155/142 +f 143/155/143 155/168/143 156/169/143 144/156/143 +f 144/156/144 156/169/144 145/157/144 133/144/144 +f 145/157/145 157/170/145 158/171/145 146/158/145 +f 146/158/146 158/171/146 159/172/146 147/159/146 +f 147/159/147 159/172/147 160/173/147 148/160/147 +f 148/160/148 160/173/148 161/174/148 149/161/148 +f 149/161/149 161/174/149 162/175/149 150/162/149 +f 150/162/150 162/175/150 163/176/150 151/163/150 +f 151/164/151 163/177/151 164/178/151 152/165/151 +f 152/165/152 164/178/152 165/179/152 153/166/152 +f 153/166/153 165/179/153 166/180/153 154/167/153 +f 154/167/154 166/180/154 167/181/154 155/168/154 +f 155/168/155 167/181/155 168/182/155 156/169/155 +f 156/169/156 168/182/156 157/170/156 145/157/156 +f 157/170/157 169/183/157 170/184/157 158/171/157 +f 158/171/158 170/184/158 171/185/158 159/172/158 +f 159/172/159 171/185/159 172/186/159 160/173/159 +f 160/173/160 172/186/160 173/187/160 161/174/160 +f 161/174/161 173/187/161 174/188/161 162/175/161 +f 162/175/162 174/188/162 175/189/162 163/176/162 +f 163/177/163 175/190/163 176/191/163 164/178/163 +f 164/178/164 176/191/164 177/192/164 165/179/164 +f 165/179/165 177/192/165 178/193/165 166/180/165 +f 166/180/166 178/193/166 179/194/166 167/181/166 +f 167/181/167 179/194/167 180/195/167 168/182/167 +f 168/182/168 180/195/168 169/183/168 157/170/168 +f 169/183/169 181/196/169 182/197/169 170/184/169 +f 170/184/170 182/197/170 183/198/170 171/185/170 +f 171/185/171 183/198/171 184/199/171 172/186/171 +f 172/186/172 184/199/172 185/200/172 173/187/172 +f 173/187/173 185/200/173 186/201/173 174/188/173 +f 174/188/174 186/201/174 187/202/174 175/189/174 +f 175/190/175 187/203/175 188/204/175 176/191/175 +f 176/191/176 188/204/176 189/205/176 177/192/176 +f 177/192/177 189/205/177 190/206/177 178/193/177 +f 178/193/178 190/206/178 191/207/178 179/194/178 +f 179/194/179 191/207/179 192/208/179 180/195/179 +f 180/195/180 192/208/180 181/196/180 169/183/180 +f 181/196/181 193/209/181 194/210/181 182/197/181 +f 182/197/182 194/210/182 195/211/182 183/198/182 +f 183/198/183 195/211/183 196/212/183 184/199/183 +f 184/199/184 196/212/184 197/213/184 185/200/184 +f 185/200/185 197/213/185 198/214/185 186/201/185 +f 186/201/186 198/214/186 199/215/186 187/202/186 +f 187/203/187 199/216/187 200/217/187 188/204/187 +f 188/204/188 200/217/188 201/218/188 189/205/188 +f 189/205/189 201/218/189 202/219/189 190/206/189 +f 190/206/190 202/219/190 203/220/190 191/207/190 +f 191/207/191 203/220/191 204/221/191 192/208/191 +f 192/208/192 204/221/192 193/209/192 181/196/192 +f 193/209/193 205/222/193 206/223/193 194/210/193 +f 194/210/194 206/223/194 207/224/194 195/211/194 +f 195/211/195 207/224/195 208/225/195 196/212/195 +f 196/212/196 208/225/196 209/226/196 197/213/196 +f 197/213/197 209/226/197 210/227/197 198/214/197 +f 198/214/198 210/227/198 211/228/198 199/215/198 +f 199/216/199 211/229/199 212/230/199 200/217/199 +f 200/217/200 212/230/200 213/231/200 201/218/200 +f 201/218/201 213/231/201 214/232/201 202/219/201 +f 202/219/202 214/232/202 215/233/202 203/220/202 +f 203/220/203 215/233/203 216/234/203 204/221/203 +f 204/221/204 216/234/204 205/222/204 193/209/204 +f 205/222/205 217/235/205 218/236/205 206/223/205 +f 206/223/206 218/236/206 219/237/206 207/224/206 +f 207/224/207 219/237/207 220/238/207 208/225/207 +f 208/225/208 220/238/208 221/239/208 209/226/208 +f 209/226/209 221/239/209 222/240/209 210/227/209 +f 210/227/210 222/240/210 223/241/210 211/228/210 +f 211/229/211 223/242/211 224/243/211 212/230/211 +f 212/230/212 224/243/212 225/244/212 213/231/212 +f 213/231/213 225/244/213 226/245/213 214/232/213 +f 214/232/214 226/245/214 227/246/214 215/233/214 +f 215/233/215 227/246/215 228/247/215 216/234/215 +f 216/234/216 228/247/216 217/235/216 205/222/216 +f 217/235/217 229/248/217 230/249/217 218/236/217 +f 218/236/218 230/249/218 231/250/218 219/237/218 +f 219/237/219 231/250/219 232/251/219 220/238/219 +f 220/238/220 232/251/220 233/252/220 221/239/220 +f 221/239/221 233/252/221 234/253/221 222/240/221 +f 222/240/222 234/253/222 235/254/222 223/241/222 +f 223/242/223 235/255/223 236/256/223 224/243/223 +f 224/243/224 236/256/224 237/257/224 225/244/224 +f 225/244/225 237/257/225 238/258/225 226/245/225 +f 226/245/226 238/258/226 239/259/226 227/246/226 +f 227/246/227 239/259/227 240/260/227 228/247/227 +f 228/247/228 240/260/228 229/248/228 217/235/228 +f 229/248/229 241/261/229 242/262/229 230/249/229 +f 230/249/230 242/262/230 243/263/230 231/250/230 +f 231/250/231 243/263/231 244/264/231 232/251/231 +f 232/251/232 244/264/232 245/265/232 233/252/232 +f 233/252/233 245/265/233 246/266/233 234/253/233 +f 234/253/234 246/266/234 247/267/234 235/254/234 +f 235/255/235 247/268/235 248/269/235 236/256/235 +f 236/256/236 248/269/236 249/270/236 237/257/236 +f 237/257/237 249/270/237 250/271/237 238/258/237 +f 238/258/238 250/271/238 251/272/238 239/259/238 +f 239/259/239 251/272/239 252/273/239 240/260/239 +f 240/260/240 252/273/240 241/261/240 229/248/240 +f 241/261/241 253/274/241 254/275/241 242/262/241 +f 242/262/242 254/275/242 255/276/242 243/263/242 +f 243/263/243 255/276/243 256/277/243 244/264/243 +f 244/264/244 256/277/244 257/278/244 245/265/244 +f 245/265/245 257/278/245 258/279/245 246/266/245 +f 246/266/246 258/279/246 259/280/246 247/267/246 +f 247/268/247 259/281/247 260/282/247 248/269/247 +f 248/269/248 260/282/248 261/283/248 249/270/248 +f 249/270/249 261/283/249 262/284/249 250/271/249 +f 250/271/250 262/284/250 263/285/250 251/272/250 +f 251/272/251 263/285/251 264/286/251 252/273/251 +f 252/273/252 264/286/252 253/274/252 241/261/252 +f 253/274/253 265/287/253 266/288/253 254/275/253 +f 254/275/254 266/288/254 267/289/254 255/276/254 +f 255/276/255 267/289/255 268/290/255 256/277/255 +f 256/277/256 268/290/256 269/291/256 257/278/256 +f 257/278/257 269/291/257 270/292/257 258/279/257 +f 258/279/258 270/292/258 271/293/258 259/280/258 +f 259/281/259 271/294/259 272/295/259 260/282/259 +f 260/282/260 272/295/260 273/296/260 261/283/260 +f 261/283/261 273/296/261 274/297/261 262/284/261 +f 262/284/262 274/297/262 275/298/262 263/285/262 +f 263/285/263 275/298/263 276/299/263 264/286/263 +f 264/286/264 276/299/264 265/287/264 253/274/264 +f 265/287/265 277/300/265 278/301/265 266/288/265 +f 266/288/266 278/301/266 279/302/266 267/289/266 +f 267/289/267 279/302/267 280/303/267 268/290/267 +f 268/290/268 280/303/268 281/304/268 269/291/268 +f 269/291/269 281/304/269 282/305/269 270/292/269 +f 270/292/270 282/305/270 283/306/270 271/293/270 +f 271/294/271 283/307/271 284/308/271 272/295/271 +f 272/295/272 284/308/272 285/309/272 273/296/272 +f 273/296/273 285/309/273 286/310/273 274/297/273 +f 274/297/274 286/310/274 287/311/274 275/298/274 +f 275/298/275 287/311/275 288/312/275 276/299/275 +f 276/299/276 288/312/276 277/300/276 265/287/276 +f 277/300/277 289/313/277 290/314/277 278/301/277 +f 278/301/278 290/314/278 291/315/278 279/302/278 +f 279/302/279 291/315/279 292/316/279 280/303/279 +f 280/303/280 292/316/280 293/317/280 281/304/280 +f 281/304/281 293/317/281 294/318/281 282/305/281 +f 282/305/282 294/318/282 295/319/282 283/306/282 +f 283/307/283 295/320/283 296/321/283 284/308/283 +f 284/308/284 296/321/284 297/322/284 285/309/284 +f 285/309/285 297/322/285 298/323/285 286/310/285 +f 286/310/286 298/323/286 299/324/286 287/311/286 +f 287/311/287 299/324/287 300/325/287 288/312/287 +f 288/312/288 300/325/288 289/313/288 277/300/288 +f 289/326/6 301/327/6 302/328/6 290/329/6 +f 290/329/5 302/328/5 303/330/5 291/331/5 +f 291/331/4 303/330/4 304/332/4 292/333/4 +f 292/333/3 304/332/3 305/334/3 293/335/3 +f 293/335/2 305/334/2 306/336/2 294/337/2 +f 294/337/1 306/336/1 307/338/1 295/339/1 +f 295/340/12 307/341/12 308/342/12 296/343/12 +f 296/343/11 308/342/11 309/344/11 297/345/11 +f 297/345/10 309/344/10 310/346/10 298/347/10 +f 298/347/9 310/346/9 311/348/9 299/349/9 +f 299/349/8 311/348/8 312/350/8 300/351/8 +f 300/351/7 312/350/7 301/327/7 289/326/7 +f 301/327/18 313/352/18 314/353/18 302/328/18 +f 302/328/17 314/353/17 315/354/17 303/330/17 +f 303/330/16 315/354/16 316/355/16 304/332/16 +f 304/332/15 316/355/15 317/356/15 305/334/15 +f 305/334/14 317/356/14 318/357/14 306/336/14 +f 306/336/13 318/357/13 319/358/13 307/338/13 +f 307/341/24 319/359/24 320/360/24 308/342/24 +f 308/342/23 320/360/23 321/361/23 309/344/23 +f 309/344/22 321/361/22 322/362/22 310/346/22 +f 310/346/21 322/362/21 323/363/21 311/348/21 +f 311/348/20 323/363/20 324/364/20 312/350/20 +f 312/350/19 324/364/19 313/352/19 301/327/19 +f 313/352/30 325/365/30 326/366/30 314/353/30 +f 314/353/29 326/366/29 327/367/29 315/354/29 +f 315/354/28 327/367/28 328/368/28 316/355/28 +f 316/355/27 328/368/27 329/369/27 317/356/27 +f 317/356/26 329/369/26 330/370/26 318/357/26 +f 318/357/25 330/370/25 331/371/25 319/358/25 +f 319/359/36 331/372/36 332/373/36 320/360/36 +f 320/360/35 332/373/35 333/374/35 321/361/35 +f 321/361/34 333/374/34 334/375/34 322/362/34 +f 322/362/33 334/375/33 335/376/33 323/363/33 +f 323/363/32 335/376/32 336/377/32 324/364/32 +f 324/364/31 336/377/31 325/365/31 313/352/31 +f 325/365/42 337/378/42 338/379/42 326/366/42 +f 326/366/41 338/379/41 339/380/41 327/367/41 +f 327/367/40 339/380/40 340/381/40 328/368/40 +f 328/368/39 340/381/39 341/382/39 329/369/39 +f 329/369/38 341/382/38 342/383/38 330/370/38 +f 330/370/37 342/383/37 343/384/37 331/371/37 +f 331/372/48 343/385/48 344/386/48 332/373/48 +f 332/373/47 344/386/47 345/387/47 333/374/47 +f 333/374/46 345/387/46 346/388/46 334/375/46 +f 334/375/45 346/388/45 347/389/45 335/376/45 +f 335/376/44 347/389/44 348/390/44 336/377/44 +f 336/377/43 348/390/43 337/378/43 325/365/43 +f 337/378/54 349/391/54 350/392/54 338/379/54 +f 338/379/53 350/392/53 351/393/53 339/380/53 +f 339/380/52 351/393/52 352/394/52 340/381/52 +f 340/381/51 352/394/51 353/395/51 341/382/51 +f 341/382/50 353/395/50 354/396/50 342/383/50 +f 342/383/49 354/396/49 355/397/49 343/384/49 +f 343/385/60 355/398/60 356/399/60 344/386/60 +f 344/386/59 356/399/59 357/400/59 345/387/59 +f 345/387/58 357/400/58 358/401/58 346/388/58 +f 346/388/57 358/401/57 359/402/57 347/389/57 +f 347/389/56 359/402/56 360/403/56 348/390/56 +f 348/390/55 360/403/55 349/391/55 337/378/55 +f 349/391/66 361/404/66 362/405/66 350/392/66 +f 350/392/65 362/405/65 363/406/65 351/393/65 +f 351/393/64 363/406/64 364/407/64 352/394/64 +f 352/394/63 364/407/63 365/408/63 353/395/63 +f 353/395/62 365/408/62 366/409/62 354/396/62 +f 354/396/61 366/409/61 367/410/61 355/397/61 +f 355/398/72 367/411/72 368/412/72 356/399/72 +f 356/399/71 368/412/71 369/413/71 357/400/71 +f 357/400/70 369/413/70 370/414/70 358/401/70 +f 358/401/69 370/414/69 371/415/69 359/402/69 +f 359/402/68 371/415/68 372/416/68 360/403/68 +f 360/403/67 372/416/67 361/404/67 349/391/67 +f 361/404/78 373/417/78 374/418/78 362/405/78 +f 362/405/77 374/418/77 375/419/77 363/406/77 +f 363/406/76 375/419/76 376/420/76 364/407/76 +f 364/407/75 376/420/75 377/421/75 365/408/75 +f 365/408/74 377/421/74 378/422/74 366/409/74 +f 366/409/73 378/422/73 379/423/73 367/410/73 +f 367/411/84 379/424/84 380/425/84 368/412/84 +f 368/412/83 380/425/83 381/426/83 369/413/83 +f 369/413/82 381/426/82 382/427/82 370/414/82 +f 370/414/81 382/427/81 383/428/81 371/415/81 +f 371/415/80 383/428/80 384/429/80 372/416/80 +f 372/416/79 384/429/79 373/417/79 361/404/79 +f 373/417/90 385/430/90 386/431/90 374/418/90 +f 374/418/89 386/431/89 387/432/89 375/419/89 +f 375/419/88 387/432/88 388/433/88 376/420/88 +f 376/420/87 388/433/87 389/434/87 377/421/87 +f 377/421/86 389/434/86 390/435/86 378/422/86 +f 378/422/85 390/435/85 391/436/85 379/423/85 +f 379/424/96 391/437/96 392/438/96 380/425/96 +f 380/425/95 392/438/95 393/439/95 381/426/95 +f 381/426/94 393/439/94 394/440/94 382/427/94 +f 382/427/93 394/440/93 395/441/93 383/428/93 +f 383/428/92 395/441/92 396/442/92 384/429/92 +f 384/429/91 396/442/91 385/430/91 373/417/91 +f 385/430/102 397/443/102 398/444/102 386/431/102 +f 386/431/101 398/444/101 399/445/101 387/432/101 +f 387/432/100 399/445/100 400/446/100 388/433/100 +f 388/433/99 400/446/99 401/447/99 389/434/99 +f 389/434/98 401/447/98 402/448/98 390/435/98 +f 390/435/97 402/448/97 403/449/97 391/436/97 +f 391/437/108 403/450/108 404/451/108 392/438/108 +f 392/438/107 404/451/107 405/452/107 393/439/107 +f 393/439/106 405/452/106 406/453/106 394/440/106 +f 394/440/105 406/453/105 407/454/105 395/441/105 +f 395/441/104 407/454/104 408/455/104 396/442/104 +f 396/442/103 408/455/103 397/443/103 385/430/103 +f 397/443/114 409/456/114 410/457/114 398/444/114 +f 398/444/113 410/457/113 411/458/113 399/445/113 +f 399/445/112 411/458/112 412/459/112 400/446/112 +f 400/446/111 412/459/111 413/460/111 401/447/111 +f 401/447/110 413/460/110 414/461/110 402/448/110 +f 402/448/109 414/461/109 415/462/109 403/449/109 +f 403/450/120 415/463/120 416/464/120 404/451/120 +f 404/451/119 416/464/119 417/465/119 405/452/119 +f 405/452/118 417/465/118 418/466/118 406/453/118 +f 406/453/117 418/466/117 419/467/117 407/454/117 +f 407/454/116 419/467/116 420/468/116 408/455/116 +f 408/455/115 420/468/115 409/456/115 397/443/115 +f 409/456/126 421/469/126 422/470/126 410/457/126 +f 410/457/125 422/470/125 423/471/125 411/458/125 +f 411/458/124 423/471/124 424/472/124 412/459/124 +f 412/459/123 424/472/123 425/473/123 413/460/123 +f 413/460/122 425/473/122 426/474/122 414/461/122 +f 414/461/121 426/474/121 427/475/121 415/462/121 +f 415/463/132 427/476/132 428/477/132 416/464/132 +f 416/464/131 428/477/131 429/478/131 417/465/131 +f 417/465/130 429/478/130 430/479/130 418/466/130 +f 418/466/129 430/479/129 431/480/129 419/467/129 +f 419/467/128 431/480/128 432/481/128 420/468/128 +f 420/468/127 432/481/127 421/469/127 409/456/127 +f 421/469/138 433/482/138 434/483/138 422/470/138 +f 422/470/137 434/483/137 435/484/137 423/471/137 +f 423/471/136 435/484/136 436/485/136 424/472/136 +f 424/472/135 436/485/135 437/486/135 425/473/135 +f 425/473/134 437/486/134 438/487/134 426/474/134 +f 426/474/133 438/487/133 439/488/133 427/475/133 +f 427/476/144 439/489/144 440/490/144 428/477/144 +f 428/477/143 440/490/143 441/491/143 429/478/143 +f 429/478/142 441/491/142 442/492/142 430/479/142 +f 430/479/141 442/492/141 443/493/141 431/480/141 +f 431/480/140 443/493/140 444/494/140 432/481/140 +f 432/481/139 444/494/139 433/482/139 421/469/139 +f 433/482/150 445/495/150 446/496/150 434/483/150 +f 434/483/149 446/496/149 447/497/149 435/484/149 +f 435/484/148 447/497/148 448/498/148 436/485/148 +f 436/485/147 448/498/147 449/499/147 437/486/147 +f 437/486/146 449/499/146 450/500/146 438/487/146 +f 438/487/145 450/500/145 451/501/145 439/488/145 +f 439/489/156 451/502/156 452/503/156 440/490/156 +f 440/490/155 452/503/155 453/504/155 441/491/155 +f 441/491/154 453/504/154 454/505/154 442/492/154 +f 442/492/153 454/505/153 455/506/153 443/493/153 +f 443/493/152 455/506/152 456/507/152 444/494/152 +f 444/494/151 456/507/151 445/495/151 433/482/151 +f 445/495/162 457/508/162 458/509/162 446/496/162 +f 446/496/161 458/509/161 459/510/161 447/497/161 +f 447/497/160 459/510/160 460/511/160 448/498/160 +f 448/498/159 460/511/159 461/512/159 449/499/159 +f 449/499/158 461/512/158 462/513/158 450/500/158 +f 450/500/157 462/513/157 463/514/157 451/501/157 +f 451/502/168 463/515/168 464/516/168 452/503/168 +f 452/503/167 464/516/167 465/517/167 453/504/167 +f 453/504/166 465/517/166 466/518/166 454/505/166 +f 454/505/165 466/518/165 467/519/165 455/506/165 +f 455/506/164 467/519/164 468/520/164 456/507/164 +f 456/507/163 468/520/163 457/508/163 445/495/163 +f 457/508/174 469/521/174 470/522/174 458/509/174 +f 458/509/173 470/522/173 471/523/173 459/510/173 +f 459/510/172 471/523/172 472/524/172 460/511/172 +f 460/511/171 472/524/171 473/525/171 461/512/171 +f 461/512/170 473/525/170 474/526/170 462/513/170 +f 462/513/169 474/526/169 475/527/169 463/514/169 +f 463/515/180 475/528/180 476/529/180 464/516/180 +f 464/516/179 476/529/179 477/530/179 465/517/179 +f 465/517/178 477/530/178 478/531/178 466/518/178 +f 466/518/177 478/531/177 479/532/177 467/519/177 +f 467/519/176 479/532/176 480/533/176 468/520/176 +f 468/520/175 480/533/175 469/521/175 457/508/175 +f 469/521/186 481/534/186 482/535/186 470/522/186 +f 470/522/185 482/535/185 483/536/185 471/523/185 +f 471/523/184 483/536/184 484/537/184 472/524/184 +f 472/524/183 484/537/183 485/538/183 473/525/183 +f 473/525/182 485/538/182 486/539/182 474/526/182 +f 474/526/181 486/539/181 487/540/181 475/527/181 +f 475/528/192 487/541/192 488/542/192 476/529/192 +f 476/529/191 488/542/191 489/543/191 477/530/191 +f 477/530/190 489/543/190 490/544/190 478/531/190 +f 478/531/189 490/544/189 491/545/189 479/532/189 +f 479/532/188 491/545/188 492/546/188 480/533/188 +f 480/533/187 492/546/187 481/534/187 469/521/187 +f 481/534/198 493/547/198 494/548/198 482/535/198 +f 482/535/197 494/548/197 495/549/197 483/536/197 +f 483/536/196 495/549/196 496/550/196 484/537/196 +f 484/537/195 496/550/195 497/551/195 485/538/195 +f 485/538/194 497/551/194 498/552/194 486/539/194 +f 486/539/193 498/552/193 499/553/193 487/540/193 +f 487/541/204 499/554/204 500/555/204 488/542/204 +f 488/542/203 500/555/203 501/556/203 489/543/203 +f 489/543/202 501/556/202 502/557/202 490/544/202 +f 490/544/201 502/557/201 503/558/201 491/545/201 +f 491/545/200 503/558/200 504/559/200 492/546/200 +f 492/546/199 504/559/199 493/547/199 481/534/199 +f 493/547/210 505/560/210 506/561/210 494/548/210 +f 494/548/209 506/561/209 507/562/209 495/549/209 +f 495/549/208 507/562/208 508/563/208 496/550/208 +f 496/550/207 508/563/207 509/564/207 497/551/207 +f 497/551/206 509/564/206 510/565/206 498/552/206 +f 498/552/205 510/565/205 511/566/205 499/553/205 +f 499/554/216 511/567/216 512/568/216 500/555/216 +f 500/555/215 512/568/215 513/569/215 501/556/215 +f 501/556/214 513/569/214 514/570/214 502/557/214 +f 502/557/213 514/570/213 515/571/213 503/558/213 +f 503/558/212 515/571/212 516/572/212 504/559/212 +f 504/559/211 516/572/211 505/560/211 493/547/211 +f 505/560/222 517/573/222 518/574/222 506/561/222 +f 506/561/221 518/574/221 519/575/221 507/562/221 +f 507/562/220 519/575/220 520/576/220 508/563/220 +f 508/563/219 520/576/219 521/577/219 509/564/219 +f 509/564/218 521/577/218 522/578/218 510/565/218 +f 510/565/217 522/578/217 523/579/217 511/566/217 +f 511/567/228 523/580/228 524/581/228 512/568/228 +f 512/568/227 524/581/227 525/582/227 513/569/227 +f 513/569/226 525/582/226 526/583/226 514/570/226 +f 514/570/225 526/583/225 527/584/225 515/571/225 +f 515/571/224 527/584/224 528/585/224 516/572/224 +f 516/572/223 528/585/223 517/573/223 505/560/223 +f 517/573/234 529/586/234 530/587/234 518/574/234 +f 518/574/233 530/587/233 531/588/233 519/575/233 +f 519/575/232 531/588/232 532/589/232 520/576/232 +f 520/576/231 532/589/231 533/590/231 521/577/231 +f 521/577/230 533/590/230 534/591/230 522/578/230 +f 522/578/229 534/591/229 535/592/229 523/579/229 +f 523/580/240 535/593/240 536/594/240 524/581/240 +f 524/581/239 536/594/239 537/595/239 525/582/239 +f 525/582/238 537/595/238 538/596/238 526/583/238 +f 526/583/237 538/596/237 539/597/237 527/584/237 +f 527/584/236 539/597/236 540/598/236 528/585/236 +f 528/585/235 540/598/235 529/586/235 517/573/235 +f 529/586/246 541/599/246 542/600/246 530/587/246 +f 530/587/245 542/600/245 543/601/245 531/588/245 +f 531/588/244 543/601/244 544/602/244 532/589/244 +f 532/589/243 544/602/243 545/603/243 533/590/243 +f 533/590/242 545/603/242 546/604/242 534/591/242 +f 534/591/241 546/604/241 547/605/241 535/592/241 +f 535/593/252 547/606/252 548/607/252 536/594/252 +f 536/594/251 548/607/251 549/608/251 537/595/251 +f 537/595/250 549/608/250 550/609/250 538/596/250 +f 538/596/249 550/609/249 551/610/249 539/597/249 +f 539/597/248 551/610/248 552/611/248 540/598/248 +f 540/598/247 552/611/247 541/599/247 529/586/247 +f 541/599/258 553/612/258 554/613/258 542/600/258 +f 542/600/257 554/613/257 555/614/257 543/601/257 +f 543/601/256 555/614/256 556/615/256 544/602/256 +f 544/602/255 556/615/255 557/616/255 545/603/255 +f 545/603/254 557/616/254 558/617/254 546/604/254 +f 546/604/253 558/617/253 559/618/253 547/605/253 +f 547/606/264 559/619/264 560/620/264 548/607/264 +f 548/607/263 560/620/263 561/621/263 549/608/263 +f 549/608/262 561/621/262 562/622/262 550/609/262 +f 550/609/261 562/622/261 563/623/261 551/610/261 +f 551/610/260 563/623/260 564/624/260 552/611/260 +f 552/611/259 564/624/259 553/612/259 541/599/259 +f 553/612/270 565/625/270 566/626/270 554/613/270 +f 554/613/269 566/626/269 567/627/269 555/614/269 +f 555/614/268 567/627/268 568/628/268 556/615/268 +f 556/615/267 568/628/267 569/629/267 557/616/267 +f 557/616/266 569/629/266 570/630/266 558/617/266 +f 558/617/265 570/630/265 571/631/265 559/618/265 +f 559/619/276 571/632/276 572/633/276 560/620/276 +f 560/620/275 572/633/275 573/634/275 561/621/275 +f 561/621/274 573/634/274 574/635/274 562/622/274 +f 562/622/273 574/635/273 575/636/273 563/623/273 +f 563/623/272 575/636/272 576/637/272 564/624/272 +f 564/624/271 576/637/271 565/625/271 553/612/271 +f 565/625/282 1/1/282 2/4/282 566/626/282 +f 566/626/281 2/4/281 3/6/281 567/627/281 +f 567/627/280 3/6/280 4/8/280 568/628/280 +f 568/628/279 4/8/279 5/10/279 569/629/279 +f 569/629/278 5/10/278 6/12/278 570/630/278 +f 570/630/277 6/12/277 7/14/277 571/631/277 +f 571/632/288 7/15/288 8/18/288 572/633/288 +f 572/633/287 8/18/287 9/20/287 573/634/287 +f 573/634/286 9/20/286 10/22/286 574/635/286 +f 574/635/285 10/22/285 11/24/285 575/636/285 +f 575/636/284 11/24/284 12/26/284 576/637/284 +f 576/637/283 12/26/283 1/1/283 565/625/283 diff --git a/sdformat_test_files/models/geometry_mesh_scaled/geometry_mesh_scaled.sdf b/sdformat_test_files/models/geometry_mesh_scaled/geometry_mesh_scaled.sdf new file mode 100644 index 00000000..e799b5b0 --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_scaled/geometry_mesh_scaled.sdf @@ -0,0 +1,34 @@ + + + + + + + + model://geometry_mesh_scaled/torus.stl + 0.1 0.2 0.4 + + + + + + + model://geometry_mesh_scaled/torus.stl + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/geometry_mesh_scaled/model.config b/sdformat_test_files/models/geometry_mesh_scaled/model.config new file mode 100644 index 00000000..862436ed --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_scaled/model.config @@ -0,0 +1,14 @@ + + + geometry_mesh_scaled + 1.0 + geometry_mesh_scaled.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/geometry_mesh_scaled/torus.stl b/sdformat_test_files/models/geometry_mesh_scaled/torus.stl new file mode 100644 index 0000000000000000000000000000000000000000..09ef325fd3b3f466ae87affa366583a69177ebcf GIT binary patch literal 57684 zcmbWAchn|Tm9GmVHIf9xz*P_(@s0$^AaoU=HabWKk&LIb_y5)f%IQab^n6u`(Yi+#VTI&`6AOD-XNKqVe<43A`zmsOJ zy!okRQJh_k{>+*4&Z_QMes%tTMRCMFU#zbG!fN?9{~ZMJKM<=;Bdm4YWnUWoC5X4( zwSIN|yqPn%~0Ai>$w||eGsMmb@^s9c{wlR^IIN;@bRd4v! z6EnM~TK=P_)-#?t{i@rh5ksxL^&VT?wSKexyqWX!=0!1)nE2s?v#MneyJKcI9`tJS z1Bmpp32QC+*?0Eukr6!f#*Z|I?RV1rS2Kc^n3%gqSv`0BjWgF>XX!T-#laApL%e<( zG1S_;ZKEU7#ugB-+Wgd-@f=G`s6BMB#OBbhjR9dTJuN!vtEPMN#u5|ix1LDvz5~+4 zP;1=l5ZG0H*i-EYHtOBlgvK8NyQ=?_F~<@I#87K)+ap*a#G+W@yv`CKCK3~}V~CeS z>;i#Z4Tz!E*b5-yQM~!gyt(|NHX(n6h&|l^!T%i)){-|vB$gyH5KC%HOgOGgq7Qa8 zAck6JSBXO1|Bg6gPIbx)o0r&CX{{YU^~LH}=bl$aYrXwHUtP5Ry!@O0j)8as#Q&K_ zSW8a`vC)<5R3G}#(q;P05)+TV;*-?@E1ucMtMwuFg-D;7u$Fq7Hoo=NlgsaJy4}n~ z21`slIqRtEx2Gg7C;EI1Vzte-o0$k_!dkKzh;O|0%G;(zx-hT z9+yD8ZnGB?){^DZ25;VM_@Sli#4Afo96W!EYLD}`Lp$TKF2vyw=_?b~k_ST^ea4*T zT`z22XUr`z@s=YusUEv-R@p_LqabEMWXw%i%aN!kM#L+yL`zJly?XLgv33*IQri%D z^EteEe9#gT>NkiD`re&RSWA5faTz1{WybtgB7-F+H2x6SRXgVVstpKh$$B6z#u6{W zc0*WVLUs&sDa0z+ZsL^*Yssb|HpZhq(D`6vi3#~5#CkoEcxA#`@=b^%i3}$b8D7Z< zT4KU+r5*F?O%NG#6V`H6DvHJ5azM4v3ul!}V~N&U`OeQ)_dofkGVyA)ht8<(+5PwV zH~%dMaqIJEl`o%0SW8a`@jqX9b9LDZ`KESJ{QZUf>%6%oCXU;7lWK=k{tNAl z$5$X`PVL`DI1|>A2SY6VmIInQpFgY4Y{?Q6AK!PKYTIW%)5ohtAeMOHta{aHgtZ)r zieg0kUo6oQ6Kbz6ie+fyE}km3YrO+Xz z7{Qs0U?PJhCN%yK*F)?Ek@=MgYsq>buEi2(cb3>#VnTKdaU;YwowW}LYssb|{u___ z1wObfZ*GYR`6I;n5U=iha6ni~-V8B=$naMp!;*}kB_C2I8VM4z3^g^^@)V$`TWMJikS?Nb$2iUY!H+-~tG1$?|FA zh|^YUR(|){b-tY~F>&vuYgS8t_C~Zb9&;dGy#T^m@?ePTZkyd4dhG-Cn;Ah%O#E!t z8>^QTKj`Dttq|Km#7az9%aN!kegv^C#JX6bB_`BfJ$b6trxDgt+YpEI=C9?=^Id3( z3H2L9diRwO%=8C@wbbhnUu6V;#t3HaV~GikKg8t|D;W^hlJ!8GizPnVSz=>}3E45k z%@AioB#N4_mTVe=zN%ip2e;zQEioZ~gxDYA_4wesrV-YXH$z-QWH^S%@H$4&5)+Oq zMR7O8+aXq%Mp(;HsVM$2Z=33!`^~8GTWhUTA334A;?^zOc(wfUM^(q1IkS&fOPsS! zwHCz8X@s@(gk@3ed+|!uVY}Z{R`{SLCT1W1{_5%-*Y4xh9uUVuWR_vVTIy-q`0#Ce zmS6kC3T3_rEitj-tG2Fgyf1M#@oFcC%ODc3Ojt`615w_#XMM>hR;WW*Vq)3L)~Rma zbBX>v_JjBqMCNcNtR>5*joBBk)Xd%eraFCPiHY4;U8P!U{dVpPu{Xr~AQIb6SW6xZ zQJk|)GjqQg&082jOHBNF$5&PtU-LvCuR?4A5i2oaEk~lFn3}f@D_%32L?25`sJ(jf zR7BAMVJ)={kvE^inlyLl=T){;#_?1@M1hexr_&{$$Z{s{3th>t;R zHjS{Bd=p|3BEv>RhV>aiOH4Sfv}0aX5E*k5)^b$h7w3 z5%ESW(GnACubw>Bo2C)g($hk0!<#?Kn`eGyi3#-^#J@~>cR*N6eF*U|BX|iTnE90@ zCN%yKk3(Dykyv8FTCxQQ?5f1BV!MqcCS=DD^C52PY0=2iMYSa+99Q`A>SM{~(+F!hDisA*Se*#93YKWChPl;=%&`)$PGoMi40Ei` zKTd*3%*xk<32W&I%c6LK$ny>&P&~>K6W24hdM|UV&d(o&cpJpOOe3tNo~DiOF?zQ! zigyqhEHUvT=2q)6$LiwMwGfX$WJYGfTCy10xDqS82Ww1(v&6)m%&nGUj@7-#USbF6MW9){Q!B6Cp_){+O)#?eHclZimfGJ=+v zxP-aYFPUR?@rp5T_+@L#X@s>LiHd^Xzy>R6*hQ`_F`@Qqeg`4uLj3bI!diM-h&y@n zM4-$WEHR;egSZPK@jYKfCak4CgwO~!mYC4^Lts}mcGbo!6V{R~KwOL^VpsX)Y%DP$ zJBGLgBEQgyi6*Qin}+xW9)(?1S-G>sg!~Z#yDBS)cTXd%C2xkvyys{l!-|ZcB_&O%cqS~`C8eBuNG$El_mbWGg!O2pEay*JU#`n3j~%pAgm=1rVYlt`3v7`+3mB$ z#MD$%KE@hW7q8w1@dCtarV-Y1Bw{zbClaqLF`@SAqSzMVZ?usN2ou)Q(?XoYoA1t> zXT9AL6Y4jJ^cCMZ&0D7t)>5xS%wq(1U<5PwvBZSNAL0gx_jgt@jTqZiEn9%N2us`t zOH3P<`0vV&A#R4)93l~JNQ}LxmQ6#@SLI%K6kjZjCH}keM~M9)c7tHfFd(cYZ-z)@ zVCA4%h!M2JgyRbHT?od!T4NevEyozXYgz5OmsPKy5wEQEID3PyW{)uO>QVLvS7nc| z^N&3sZiHYZbwF54Pgs(}!m8botllM`!4eY-9rRH7ID3ShpDziKReF902ZXiM)3njB z`glI8keT~fV&XOI4bEndu$y1q0P#JD%zaE)OBO>L*R$?ApVidFD@#ml!rtIh>=AbF z@goRUQ(r__OO{U?OR*YEU&RM$V-nR&?8e^UG3*g`>Y~^Mg1ww(#x%lO zY8zs4-uximoVjRYi3#-^#EibLlFwkmTIxfH3mL(SyAfo??HWhXK5>Ko)mJ z-_BE+u$C;JHdbc0J^S>D?UtB$AGufAzwgFlB?vM`+IVHcTJm7p_#;^Z$v1c_V{VCw zUy^&3tb#6HJqwX6h-Vpd6V`GhDvDVreI`~iAgm=@fWWS1-hw4&er1UX z*)hbf5IxA(xYEtvP4RskXy*t#u8#?a9Y%Mp#QvSQf>B zVWr>OZCbvD=bzQvr z1H`ouiB~49C5xer&yY9xO|k(qBeTTB%gAj{USanh4?5rk3Qc9*1G0vH&f%&Wx{`9)9cpj^Xp5-yeD3mMp#Qv2=Py3^{bWH*4qxWP z_4;ZOh>IagY$|h66V{RkL!3m_%N(j-mLd9BV&b*y9?pAg-p8vQAr6B`M!X4YIT97c z_7JJ!VMnpH#Dvgo5lpPqpd=-|M9C}Mk$c`Zng80XYt?dp7Yssb|-i$|Ow>>jU zOH9ZgA>IM82}IW0O;}6536aQfII(02M$i%yjw_SslNp%_YdI=W$I@A1^-?U+T0dQW z_4;%D{Oay6tX3aBo?m?i;y|8ivuT92^n@kflbv0)Uw4+6xN-JM^;gF8tMegtqp#NB zKNHqcPt(TvSV`)z5`8Q&amfXX);o{qS1-d7Q-_sUV!~Ro7}_`kD_OFSSC*LA_*YNN zpUkhGgIIO}gtcV(v~e6(lKuHaYfDV5de|NFC-bY>5WUw92y4lMX=5MkD)oJDU<55O z@zN7+od41B{OaWHH>!EA8WPrWB;r@0ZzGw2mY7g`by55)M51WsS0=2br-eA4H_ys> z)~_rvp?-td3nIIT=`R!3Qm;dNlo5P2BS?ipV~GikKSaiS>cmsq`IQN4$$B7CVfs=m zG2erhn2;Sq+}*{*7ZKKyO+&<^@{5)?x5R|}5#p;5+d*tFjj)z{6XHLK3?C*kyn_+6 z#DwEYQG6SMF>hDsO<2oOiFG(;;U8f}MjNHI9zXZIdZ&K<>Voy>)$5Pfua@n;CaPi@ zVJ$sj$@e+4@O7A3GHlnVEh= zW!QkQmLpO7&Dj#k#j(VM+N;N36U}1N2y5wSA^09Fv65y-JjxOi>Nkk}y04<_z77a$ zsn;PEX3SGVm{?+o35`F*_Zjoi_n--D$$B8J#S&R($hSdbi3!;;#P=q)J0Pqjn}*mC zk6IIt%52FJ6Y@uhtsvG|0AVfpCd6_?hK~|U{=#g@5)+OqtUyAff_WRp+=R6pm5Sm| z-MVP?GAwbR_2i%GWWwX6#e=*5zJA?!e~=2H`X#K9Z8D9pmY%R|SMIVdTJhCVSz_Yv z2R>A%PM}-&DOeYs*RQvmu$Fq7Hr8g9^Pz49va-a)EB|m!z1MhukTuKsS1o|BmMn%g zKFliT&8(hhMrMhL4Gz1getNt=NVVb2pF$*G)P%KU`Lw}`aCRE9B3xNwVwY3?t3GzT zKloAzYQ5SOFB8_12h&DYIhSB%o80r#5)(T<^O<_GKlo<|Doxvb1{2nDBx+aBvy$2* z`_mE=YOgMezjUj$?flAwwbV8QI}K&O)6iIALj4B8Zbpe+wHaF`tffALV8>);zhlx^ zVnX8&k+txjbyhMUtR-83cpa8FT5q?+gzUI$WBzEp-GsH|1rX0uXURTJR#+NKOvoQ0 z-q`KqBx`a&SWCVMkzJYR);^#*iZQpu#7`AhI%0WZ$vs3k6V`H6YV#TDo7quJe!I1v zpIW8azt6uq`m&Xq-;MLHX0h)aVwY)zwe*A~YXIybAIHupYkid^CZ3;Kw%K`{f3-rl z@7%6mnXs06nl>(F7kOTv&tS=bn3}48GS0v1_nq7CK@)$MmMn%g?(H%l+IVG&iGNHz zQtvg+zhXCh=6Cyi1{2nj<POm{{zyH`bHLyvmCamR1M2;6kvJ=>qsVy;~_G&7TAX3@5?KHw# zY8zsuzOS-+XNd{*8^odz$^FQRmkDdB4C~8>=@!s zh=U>WR3@w?FMzh19;R-_tBOvoQ0j)O>sX{s|#SWCVMk$TZ&e`fv45)+OqUGyOj zIcrM;!di|o)Y?!5aU2=(`Q^0M`m^?J*68a8SJ-gRW~p)gV2D%-rS{c?we*B#Q9MKy z#CBx%X9i%2i8IgJy7`ZB{os9FrA3?1V8UAJY1*K6uzr*Zh2$DoV&d6FHfa7hsUL($ z<<@kj?g5ACWVJ%0Z zu8lbmsjjiagxaf%B5kCyF}q79tfi-g(3>}wm{7k#sCNg1wbX|YH!_0X=*GOU#DvBl zB9(xtG|h^a32Vs~ATGrcug4NITe8H2>=@!!h$kTuuS{4=UH~DFYAi7!e}qUCD;1jU z_n--D$u}WBN@O^e$dL1|EHUA@LX~Mx#7az9%Q2=XQb$HTS({B|E#_7Yn(g`(bE}5G z*5~_BZP-xjl^puggthd9B^B#<(~t40%$6)M!Q3kS*sotvYuQ{6krT5_SW7)k8^o$Q zRaIGAvcv>)tBh`+&wz#0socuk$AqVryC8^iv62B{E!hIZ6{3VnTKd@f(OMI%^*g z){;#_?1)EUS2;7YvBZS@5rX>N<{AjHkOqXc%kOvuR^={?*|SKZM9y zxCv{?VrYZ2Mapk86HmOd#Ki8;Z_zA1KL6@%5Z{GJOf+FFSw3y#6px&d($sKbMr9Ol> zv>)@#WGpeE@rTHl9qRyfqK^q{$rd0u9j30a#6&ntOvsKQa!wJa+~nI}Kv+vQ4Z(U$ zb0i*>FJVhe$R8nc_RhaSWc|v7wd9)+PZ1e*>S9T4i3!IQGU6e&gh-XC32QkjG2dl{ z^Zl%JX0OOv>zrJkmZtZHA$N@u?AEHS~}VDpOc`J$=odlVwE#DukEF|?5r{;p!B zGi_L6g1y0J{qgytSrhF~dm9kelI7FJM_A$f>(*zt^D9eCus7K3JU(CaP>7sCm)rEr9<*3x2VcKMWJKqM@BKN9c zC$UUE1G!fXyN&rb|1Hce^@`LGVu=I7T6#i=FSCQZ3p>g2C`(L`dzD?&{#?%UAnxJx z)_mibu$Fq7Htu5w`Dk{MGh4F61i4oYyT54XyuKSCWp z$Aqyt2fE>==U6zw2W<+Z_%sNKNX?i44m#f|i(YTq%lVyim=WSTZ22<)}p5J!4KYlWf3b0$PjQ_U7UKejIY! zo4dyMZhLdX_Xt$Zc=FJ-#0&S%AAhWVU3&TCy10pc1f5Jz1iUB__yiZ#Ep?k8?T1 zr4WgtCafjP@A|5mMW$Z*$`TXgwl}Mc@5f1H<|z=VT{2-Uc`$8o-$b<{nR@xfvBU(q z?ah)WjPAz?k<8-E!cADqk*I4UMDnjJF`@SA$y4P-QWMrv+Yov4lX>&h16X20{nitG z?+yrSsShE(HyOdk5)&GKh_6FX%^E8i5Z00{KycqgeO+g}jU^^z#}HRR9J&C)TC!<~ z)TF)?k4im`B_`yL5UH~~3?g5UCafjjgh(velvuJ7BWQ^U#}z6RARZ%@Y~>_bz<}BD>)xtfeP}h&^3RB}C>| zmYAS+u(^BvyVmRSMYAgSn{&Dwz)V<6Jxv=cQZunVl@N(nLy7k{Y9|umhLQM)AkL9Scm`m-%i;0PrEWhik>RnVq zB>D^`6N1{oX5K44+mA=)Ro{om|21JPc`$9{-lYSngvk8L5))=sr9=2_S9e9 z50Q9f!di|*)VTLV=2t_>a3-v!wjt6-S9X1s`*B7wyf&fnfJh&ucQa=& zVJ-C`L`HBC#vHrKZ8xLeA|&JS;NRo%=iiG%ysER3X~aZJ)&r4>t+P7YZHAHwAW?cgTKe4^5#Rygpfb>1h=KN_j#GHmV6T;^`d7H88YUUm~dR_ zV#$>dSpzU(EytLSNDX0TOAFBADLAXXn_uPM=;WTb&-T`C!diMl2&|;}R%a!-e{dZ8 zO!PfcckwE{`oK9e=O=5@#87M8)3lMB{$eGW$!Kg#6TL0)9*I{ALwufCl8h}AL#?sJ zKv3&kE`^mO`p8C06TMB(@7`l&h`(ZqxgW>GP-|@Yw2?R76f4P>uzaF4(RNbevu$UNXO(IbjuWs$ys232`+P|yz z&>1~dtlfmQ)HXVK^NYIQ!Q3V|is7{h^;=J*ck@+bVyHD94~SPVf=4idS-(>6=KjIN zu8ebPQZsKyJGTiEeag95Ng|wyq1M>0AaY~jsn~92WU`XM-<2IhtN<~q`yCt*L#?rY zKqOwpqvDIQ_EA)e-;E*$+6Di`2fx|<4h{%;ZSD*lc{4<6Qa{(ll7YlTAAQmW|4W4X zCIoghAck6#nbUYi*4`{HBY4OO{U? z>@-xbVqG+I2TM#G&;H=Ms3GjeBXyR`Kx9T{!dmiR+QwcS%iZ&VuACb+mrf64p}N5P9>L^XAzf zw8Vt^4I=C9%k`_yCak4Cgy8|0hx%Or6V{SVL!`oV34Ac~EK5wtA0aqlvsnm2D_*hc+FJ5Wh$UG)e~?&`j1)^u zIIeUn^ve@VwBp6zDQasu#*FhB+IVFxY6qz%ScRD&IdkM+9Yqac=O3JS+E7o{&d5wy zOHWwx%gN5@6YSB)qbxB&?O>br-}!m+8B%o^uQg#U^)zjKgB{*``dkA`Oi(-6JV$k4 z7q5~5vCtDwwlgvl){@202KNt^*Y+6@mYAS+kP3-M`gqkqoC}dJNE6nQ<vVg>wK`W#Dx42B2}ylcX=`c!dmi8h*W%qz;nIv*XFqCpEi=wxCdE!*%`IOM4#zcckwE>J01;@)7VT{OCC%c$rmlj(o43w zB_{fe%|2eG#w#_1{0ndjBnJ$?|EVuNZ0X!nVXjUrExBM_-ka%$iYtd)vCTUD^|qN=Ubv&4kPAAJaX!Ow)DU9F#i^Xnup~8v-S2sBmgAPOCbnzB zT6)5=C?4ajx8&`U18IqgTR5L#7itK*`PGvU-0;{|{hF|rdYU$oakeTi90x- zVQp#%yZP0F5Klm4@6Lp^WHGdn8ZV+;nKmpjaUbV1%%F~@dyl&zaN7Kct zPeB|6kuOLS)^a4`=Bx=Zss?QTmI<|251wj3SW9g~{FOJ)EtScBvBZS>4dQW#+#H$} zFB8^MA41&D2;R;JCNfxJLgNqdt%;Qk2y4j}Anw8ve~2aK3(^u3vSWzc!F%5V2y4lv zA+VBqQ#>kP!j_njKSHF=GPn1pcTHGJz6o(Mks%f9)On4n0b`@J3CEQ#`s9{MYGnq5 zwH#x*6CM7_JTA2v*6L4jNP9(pHbn0qd>1s_V&C3gXTn-~!jj)wW|iAAAI)i@mYC>I ztmysxV2FQ(h}W91mU@~txREUI-rzm*J(%-k`kUnjgtcTb5MSiWZX;&< ziC31G=+7MK-{VIRABM#^^v0bwomAq4jiwm1FVNi4C%gvK8t_gc>G#(Y3nOSS;P z2{d(T2otX?F(EsKxC>(c&e{irwd4g5|B6SYDmUlJSYkr{2yp^LY6!DJZ^BygO^E(% zs`kt?OH4SfbVR-)H)YICSj#bnc_Qm$StmOH+qG7IN>&@M`m?us|JV)UPKca`Y{FW4 z!m_(lk6N$x3_43p^e2M#e%_xh*5tf<6V_5s)5fi=K5|}PTUl(0iT*6KK3;ME;C${M zjFpVeziL~zmMn%g`jgn&^(#wE^e429;uY(ztn0U5kS44p%cl))$jgax?O9=#nCMTM z>&GK2&a92Lr?;B0mOPj?_G0Dy2G+wjX9O)V(Vwx`$E*JIy((FHCamR1#N7k5k-O-U zS!0O_wO5Z%5lrR%fUuU@hFFF-&u&99g)A|leuKy@e0}c@2y3YiA^H;++xe9xCN%yK z{i%*GBCI7_fZ+bY`QOA6Gl#QeKy>Ht#;zc+#GKccuZaO6Yp>-65S(pTX9Yd8B}+`m zA0b{1aS}w%Z#Q8r`6k3xM21_43|ldRmY8r{X)UqN$&p#{GGQ&pnD)-F_SUz|^sV(5 z&Tr@b!8Tr9$@%T;?*IATKRCCxUW%Q|tY4Y1mY%RAN0?pFWGEyb*%A{+bAJ2JsUhsX zqh9g95Y|#p)5dnG*kYGAYfF}x_#5Z9KS2#)H@{jPg7c7HL|97}LmR0!Oin}QSC*Lg z6X&-tMGay19_>yzM4rlowPg9U@n&}0M|U+^V&V|aZ$F3}qwag~wGgAzrcGE&9!wj* zC(mFZvIpM7m|J4vS@I9oriQT3XCTiYISp9@Fkvl6B392K3W!-)q9rEOUfteUm{XeD zcxA#`Y8zs8-u&xiDCEpcOH8QWAd>y?MTo3lnXs1n5JDq3IxVz~874IT5VDd1VJ+DL z#Cx&C2Rcg}ofaA!txd>|AvT8KJmhvp=D%evc>%->JSrIq*=exEg!~Z#yJ~O3ew_G3 z@mzO5PVXQ8N>$iF5bvEvSW8b>7R6`DI!pFhzV0kB@tf{`oZin*>xt~qo3NI8nl={M zY`giX!^&*Q5)*fjgS^x2S(D56Aol{yKOZ8|$AqUPM?+mQNcWA^(xet@i8A5)(UcKhD+EpLFr+-yk-ENbj1kmOPj?_NK<` z$TQ|t8FNcayp{WLPNasgi&q;!91c-VBdp~})ZI6cHa5m~Eis|?YEIJW+ekf*32W(T zA+VD6mdebpEHR;egE;zsA*`i7g!nUKo;=~Kg%B=421{+)R1 zb@3=mO!RjQ^?rT?L{7fQEiopnrJkmZ)2U9#U0aD)mYC@8O6ud)qY&Hx*2XIn){@20 z#uLoqUy)v+`bkk*&-&a zB@d>JPf{ndKNU9IN>W;4qQ6nAk5}Bgl)JXtJCRIS%aMrHL5Nh?WPi{S6Kbz6ihqYV z2qI^Tn6Q@GhWK&cSGfb!5)h=@!Qh*TY>4HMRqO+)ODM`c#IG5=X&LjDMGDnz~>vo~SF zTJlYZ!-)*s=heK85wygF<4RGS32_v}FRCG7EytMgjfKtg)%gCwHb(Wg6t@5FZ!+xt zqrWe;Y41zzZdHAemY%R=XA~>R4NA!=vc!M4zmc)`^H)M_1d*&s6V_5s)5h*t$xHg^ zV~L6WE=ry@^Q)^myUK6W=>EaBb!*9DAo`my+x06;O!PNo_V1DVQmGD$wO1yrCCjIc z+?Sfj!|&keHo^99ndoo&?8oCYh(x!nxBG8dOCC%cxi6JkulDQC5)=I$r+vKY?@MiW z6irymk!XBhYL(fNB_`BfJ-#os;+C-iVJ)={k$WvO1CK{pVnY1}@o|XcASYg#u$KA| zqQCLBjaQbK(D*~hN=7#pW&~?%$rd^yzk_YOvc!b!7~=RYini-lCafhdfY<?(?vG7IPa!RGD!)>`X6 z&c52YU%&biXI~}1zWe^j?R7Z^BI{QstfeO`xqF#ec`C!r5299j{+K1JU0THz2Gfi=mC%yIFV}eJn9?J!fB~ zZln7i9(%*wVUCN%yKUxAnp zfh7(IYsnTMF2NGd?Y{>tF(EsK_$>r?XV&>1G+`}y0mSxrRPJhIkA8Gpa~nlX$R8n& zfWQ))m%qN`Fv*u|?qK;-s1vhD|jwe*A~wPdVvX1zW021`sVbkIZP%!IYn)3k9oYvH-|E%C|{6R+WH(b?1xcJr$xAie>S^(zzBlEu(QzslKu-C1H{ z6V4WWiW^zMGW-GsGd`Lyv@swPuIn7*>a#BQ7|dJHv$-FQ$tSaTX%mA*1z zEqO3)JjJ>wtDMzhjG!eZ-ox3VIW@0azxp}E42YaSW5QaFMC9B-EDe!NKub)hy}G*z zGf%b5G{RbH8-msII;R!p%mGVGsNW!-qIXk6m<$LL)>0orY{LkqhA>}VmYC4^L&QpQ zvg35ZTCxR*R2z;~&n+<_JBHv4$eBD<`#osFTC!<~+`M=Z9+l{0i3#~5#0#9&_XUVV zI1|>AZ$jkcy`0&%J|k#}3CEQ#`lRYGV{XD)j!K+?&Av00TMe`D(ppnft5hGPhA{E! zSk7+$Ej5Ilf9wR2J;+o@o3NIiu*9y|Mb7D}@j**WOie9Y?L-Y>=jV%eJJl~Dtfii& zjq}JHIJ?hhu*AgF)D+buWMUNg9_0SPnVfc;->7OxOtfS%9Wnp1K0Cn@|J|vnN6OjM z5O(juZutC*7f4LBWcjqgj(hf<+u4#O{<||cyFK+M-FPelaR5Z_<}hI`c`$A4!oD+i z1Lj_U(h?I>Q%(8UtT*=YYF`LW&aT#;Mp(;{sI{v)ITPd|*Or)2d-de0$O;<}*3#2L zko!@m-ZCf3SziYm&W_S>KQtdr>W$hFBJlN={L}2QBg6l|Mq{Cd?xjKv+xO z46z51A?K^JD^puy!f}OaCy2Wsp5c4YgtZ)FxMH0wy;KBlfF)Y%``nH5u}89(#-0^- zq7|VJ%qeVpH(yC!m1BdZfU)g%sDOCC%c?SMk?H8m8Ysq>bE|^#%ZH%p?HX%EP z_$mZ;)y}U>SW8|2K?Zi~gUN5V#Dx420!u9Et0uR3n6Q?76Jit@nETY0m~dPv3T{2A za_2;{UQAfaF@}{p>Lzll&azmdwcfBjYO#F_!2cP2( z!ft+*yS%9NYU7m&Ysq40<8rDX9_wl|Doadk$K8W_a0g-c9$$mFxv$_cVJ%rcZ9Lpn zBDJgMmYBGcy9XcQ4#I9cZid*ct4gU%SW6yE8{Ed$Fy>Y6$Fao3CEPuD6?YJJ--8E3 zd;%hOBAKw3BM~PdKztH{Ib3at3AI7LLxy5V;-aH;S@}z0Sn>&!TjP>mYCR(yPa>OhOmoQ4?SXlys%oF=R#FMvpG`0wzj>`ho=LjDM` zGeqimvrlirTJlYZ+@j3XDP*Zo*oQF<3ma{EFE=x000B+V9h+ zR|^-bw(;sWKRK;BVSN4---6Xf5Nk~%tfeO`yL;k3#!Ni7b6H|yhXanGz2$m8&lk~t z5Sfvgu$Fq7HgfI1U+oRScTRi$l?iLf zgK2{?Z)P$R&zM_cf;+gXmlQwf<5h^%_hnbcgtZ)rx;A>Ew#0VnY1}u{#8(s^m1p0bwomAq3xo?U*MrSYkrs4^cwo4536g6V{R~KyW%t zP93U4SYkqU43V1DuXVONAgm>uhM*F#%9&1ySC*KNKSJcR9#(Sd_KIfEr8*c+@CJ7{#i=s^&xLd0uLSW7)k8(HD}BP*TRAGE~8 zo~ImGtu{Vi^h*$5hDaU3{@hu~fUuTqp(Dyv1SVctVnTKdk()5F#QB-SnXr~@ z8sbBERH|~ber1UX`6C2t?G+W8In!xCSWCVMF^UYCUs+zV8%C;C`og50a>4r&Oy_h=xtgh(4EtR>5*jpThi!A^3%?kq9ENxs$g)DU*#(N<=% zTb+6w6V{Rk(*`FGH;Yo=mphRxF~RA^)&2b$##F3B+|6z^xlsecT8>2BsoBYuNiL2h zCe$A9l6`IRCUUC$fUuUH7J^)c<`3O1m5n7P)Nc?u6?omQuLgv*)Q1rB8NpS$5o|0m zq49^f6=HVs4TvQstR-83;5NZ>Z!9s<#}X5=V~8sua1U?Q9eYv~Eg_T>8NNHX=3vu%lq zv#MCjoJ3r_C!78WY=fo@%)>2Q?#y82(+khIv#1czP>~i}F)mOWFOdvSrzub=8 zzI+dwu$C+aBH5*zP#u=&V~GiF7^vRR-J1fDdjWD=LE123Em=MUcPKRPAX6`q+7c7o zx=<}k4PiGPsmz=Uk=`|7EqO3)hA(CNg z!di|*%w!;T>)Oa^?Bm#HLhaS8UqLJnk$7doT5202Z_fRLdGnm#K6;Pbk2C6@++#Bu z4~S9k<_pqgRbXGDTtR-83xCl$U7E8?h$`TW@V+d*o z%VaMnUYW3#Y#JhWa~z6CW%b+=6Y@uhwISv}V2K05TJlW@MTVT;KAPjyCLC8L(I+eP zCamQc)7_#}Q=gHQ32TwrTP0TIf85$L`ghq8{{smMot(;(Ob7wG+8baO7)9CImN8X*@#o_rwhdYsrK8 zOR4@mlxn? + + + + + + + model://geometry_mesh_stl/torus.stl + 0.1 0.1 0.1 + + + + + + + model://geometry_mesh_stl/torus.stl + 0.1 0.1 0.1 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/geometry_mesh_stl/model.config b/sdformat_test_files/models/geometry_mesh_stl/model.config new file mode 100644 index 00000000..3d884789 --- /dev/null +++ b/sdformat_test_files/models/geometry_mesh_stl/model.config @@ -0,0 +1,15 @@ + + + geometry_mesh_stl + 1.0 + geometry_mesh_stl.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Single link using an STL mesh. + + diff --git a/sdformat_test_files/models/geometry_mesh_stl/torus.stl b/sdformat_test_files/models/geometry_mesh_stl/torus.stl new file mode 100644 index 0000000000000000000000000000000000000000..09ef325fd3b3f466ae87affa366583a69177ebcf GIT binary patch literal 57684 zcmbWAchn|Tm9GmVHIf9xz*P_(@s0$^AaoU=HabWKk&LIb_y5)f%IQab^n6u`(Yi+#VTI&`6AOD-XNKqVe<43A`zmsOJ zy!okRQJh_k{>+*4&Z_QMes%tTMRCMFU#zbG!fN?9{~ZMJKM<=;Bdm4YWnUWoC5X4( zwSIN|yqPn%~0Ai>$w||eGsMmb@^s9c{wlR^IIN;@bRd4v! z6EnM~TK=P_)-#?t{i@rh5ksxL^&VT?wSKexyqWX!=0!1)nE2s?v#MneyJKcI9`tJS z1Bmpp32QC+*?0Eukr6!f#*Z|I?RV1rS2Kc^n3%gqSv`0BjWgF>XX!T-#laApL%e<( zG1S_;ZKEU7#ugB-+Wgd-@f=G`s6BMB#OBbhjR9dTJuN!vtEPMN#u5|ix1LDvz5~+4 zP;1=l5ZG0H*i-EYHtOBlgvK8NyQ=?_F~<@I#87K)+ap*a#G+W@yv`CKCK3~}V~CeS z>;i#Z4Tz!E*b5-yQM~!gyt(|NHX(n6h&|l^!T%i)){-|vB$gyH5KC%HOgOGgq7Qa8 zAck6JSBXO1|Bg6gPIbx)o0r&CX{{YU^~LH}=bl$aYrXwHUtP5Ry!@O0j)8as#Q&K_ zSW8a`vC)<5R3G}#(q;P05)+TV;*-?@E1ucMtMwuFg-D;7u$Fq7Hoo=NlgsaJy4}n~ z21`slIqRtEx2Gg7C;EI1Vzte-o0$k_!dkKzh;O|0%G;(zx-hT z9+yD8ZnGB?){^DZ25;VM_@Sli#4Afo96W!EYLD}`Lp$TKF2vyw=_?b~k_ST^ea4*T zT`z22XUr`z@s=YusUEv-R@p_LqabEMWXw%i%aN!kM#L+yL`zJly?XLgv33*IQri%D z^EteEe9#gT>NkiD`re&RSWA5faTz1{WybtgB7-F+H2x6SRXgVVstpKh$$B6z#u6{W zc0*WVLUs&sDa0z+ZsL^*Yssb|HpZhq(D`6vi3#~5#CkoEcxA#`@=b^%i3}$b8D7Z< zT4KU+r5*F?O%NG#6V`H6DvHJ5azM4v3ul!}V~N&U`OeQ)_dofkGVyA)ht8<(+5PwV zH~%dMaqIJEl`o%0SW8a`@jqX9b9LDZ`KESJ{QZUf>%6%oCXU;7lWK=k{tNAl z$5$X`PVL`DI1|>A2SY6VmIInQpFgY4Y{?Q6AK!PKYTIW%)5ohtAeMOHta{aHgtZ)r zieg0kUo6oQ6Kbz6ie+fyE}km3YrO+Xz z7{Qs0U?PJhCN%yK*F)?Ek@=MgYsq>buEi2(cb3>#VnTKdaU;YwowW}LYssb|{u___ z1wObfZ*GYR`6I;n5U=iha6ni~-V8B=$naMp!;*}kB_C2I8VM4z3^g^^@)V$`TWMJikS?Nb$2iUY!H+-~tG1$?|FA zh|^YUR(|){b-tY~F>&vuYgS8t_C~Zb9&;dGy#T^m@?ePTZkyd4dhG-Cn;Ah%O#E!t z8>^QTKj`Dttq|Km#7az9%aN!kegv^C#JX6bB_`BfJ$b6trxDgt+YpEI=C9?=^Id3( z3H2L9diRwO%=8C@wbbhnUu6V;#t3HaV~GikKg8t|D;W^hlJ!8GizPnVSz=>}3E45k z%@AioB#N4_mTVe=zN%ip2e;zQEioZ~gxDYA_4wesrV-YXH$z-QWH^S%@H$4&5)+Oq zMR7O8+aXq%Mp(;HsVM$2Z=33!`^~8GTWhUTA334A;?^zOc(wfUM^(q1IkS&fOPsS! zwHCz8X@s@(gk@3ed+|!uVY}Z{R`{SLCT1W1{_5%-*Y4xh9uUVuWR_vVTIy-q`0#Ce zmS6kC3T3_rEitj-tG2Fgyf1M#@oFcC%ODc3Ojt`615w_#XMM>hR;WW*Vq)3L)~Rma zbBX>v_JjBqMCNcNtR>5*joBBk)Xd%eraFCPiHY4;U8P!U{dVpPu{Xr~AQIb6SW6xZ zQJk|)GjqQg&082jOHBNF$5&PtU-LvCuR?4A5i2oaEk~lFn3}f@D_%32L?25`sJ(jf zR7BAMVJ)={kvE^inlyLl=T){;#_?1@M1hexr_&{$$Z{s{3th>t;R zHjS{Bd=p|3BEv>RhV>aiOH4Sfv}0aX5E*k5)^b$h7w3 z5%ESW(GnACubw>Bo2C)g($hk0!<#?Kn`eGyi3#-^#J@~>cR*N6eF*U|BX|iTnE90@ zCN%yKk3(Dykyv8FTCxQQ?5f1BV!MqcCS=DD^C52PY0=2iMYSa+99Q`A>SM{~(+F!hDisA*Se*#93YKWChPl;=%&`)$PGoMi40Ei` zKTd*3%*xk<32W&I%c6LK$ny>&P&~>K6W24hdM|UV&d(o&cpJpOOe3tNo~DiOF?zQ! zigyqhEHUvT=2q)6$LiwMwGfX$WJYGfTCy10xDqS82Ww1(v&6)m%&nGUj@7-#USbF6MW9){Q!B6Cp_){+O)#?eHclZimfGJ=+v zxP-aYFPUR?@rp5T_+@L#X@s>LiHd^Xzy>R6*hQ`_F`@Qqeg`4uLj3bI!diM-h&y@n zM4-$WEHR;egSZPK@jYKfCak4CgwO~!mYC4^Lts}mcGbo!6V{R~KwOL^VpsX)Y%DP$ zJBGLgBEQgyi6*Qin}+xW9)(?1S-G>sg!~Z#yDBS)cTXd%C2xkvyys{l!-|ZcB_&O%cqS~`C8eBuNG$El_mbWGg!O2pEay*JU#`n3j~%pAgm=1rVYlt`3v7`+3mB$ z#MD$%KE@hW7q8w1@dCtarV-Y1Bw{zbClaqLF`@SAqSzMVZ?usN2ou)Q(?XoYoA1t> zXT9AL6Y4jJ^cCMZ&0D7t)>5xS%wq(1U<5PwvBZSNAL0gx_jgt@jTqZiEn9%N2us`t zOH3P<`0vV&A#R4)93l~JNQ}LxmQ6#@SLI%K6kjZjCH}keM~M9)c7tHfFd(cYZ-z)@ zVCA4%h!M2JgyRbHT?od!T4NevEyozXYgz5OmsPKy5wEQEID3PyW{)uO>QVLvS7nc| z^N&3sZiHYZbwF54Pgs(}!m8botllM`!4eY-9rRH7ID3ShpDziKReF902ZXiM)3njB z`glI8keT~fV&XOI4bEndu$y1q0P#JD%zaE)OBO>L*R$?ApVidFD@#ml!rtIh>=AbF z@goRUQ(r__OO{U?OR*YEU&RM$V-nR&?8e^UG3*g`>Y~^Mg1ww(#x%lO zY8zs4-uximoVjRYi3#-^#EibLlFwkmTIxfH3mL(SyAfo??HWhXK5>Ko)mJ z-_BE+u$C;JHdbc0J^S>D?UtB$AGufAzwgFlB?vM`+IVHcTJm7p_#;^Z$v1c_V{VCw zUy^&3tb#6HJqwX6h-Vpd6V`GhDvDVreI`~iAgm=@fWWS1-hw4&er1UX z*)hbf5IxA(xYEtvP4RskXy*t#u8#?a9Y%Mp#QvSQf>B zVWr>OZCbvD=bzQvr z1H`ouiB~49C5xer&yY9xO|k(qBeTTB%gAj{USanh4?5rk3Qc9*1G0vH&f%&Wx{`9)9cpj^Xp5-yeD3mMp#Qv2=Py3^{bWH*4qxWP z_4;ZOh>IagY$|h66V{RkL!3m_%N(j-mLd9BV&b*y9?pAg-p8vQAr6B`M!X4YIT97c z_7JJ!VMnpH#Dvgo5lpPqpd=-|M9C}Mk$c`Zng80XYt?dp7Yssb|-i$|Ow>>jU zOH9ZgA>IM82}IW0O;}6536aQfII(02M$i%yjw_SslNp%_YdI=W$I@A1^-?U+T0dQW z_4;%D{Oay6tX3aBo?m?i;y|8ivuT92^n@kflbv0)Uw4+6xN-JM^;gF8tMegtqp#NB zKNHqcPt(TvSV`)z5`8Q&amfXX);o{qS1-d7Q-_sUV!~Ro7}_`kD_OFSSC*LA_*YNN zpUkhGgIIO}gtcV(v~e6(lKuHaYfDV5de|NFC-bY>5WUw92y4lMX=5MkD)oJDU<55O z@zN7+od41B{OaWHH>!EA8WPrWB;r@0ZzGw2mY7g`by55)M51WsS0=2br-eA4H_ys> z)~_rvp?-td3nIIT=`R!3Qm;dNlo5P2BS?ipV~GikKSaiS>cmsq`IQN4$$B7CVfs=m zG2erhn2;Sq+}*{*7ZKKyO+&<^@{5)?x5R|}5#p;5+d*tFjj)z{6XHLK3?C*kyn_+6 z#DwEYQG6SMF>hDsO<2oOiFG(;;U8f}MjNHI9zXZIdZ&K<>Voy>)$5Pfua@n;CaPi@ zVJ$sj$@e+4@O7A3GHlnVEh= zW!QkQmLpO7&Dj#k#j(VM+N;N36U}1N2y5wSA^09Fv65y-JjxOi>Nkk}y04<_z77a$ zsn;PEX3SGVm{?+o35`F*_Zjoi_n--D$$B8J#S&R($hSdbi3!;;#P=q)J0Pqjn}*mC zk6IIt%52FJ6Y@uhtsvG|0AVfpCd6_?hK~|U{=#g@5)+OqtUyAff_WRp+=R6pm5Sm| z-MVP?GAwbR_2i%GWWwX6#e=*5zJA?!e~=2H`X#K9Z8D9pmY%R|SMIVdTJhCVSz_Yv z2R>A%PM}-&DOeYs*RQvmu$Fq7Hr8g9^Pz49va-a)EB|m!z1MhukTuKsS1o|BmMn%g zKFliT&8(hhMrMhL4Gz1getNt=NVVb2pF$*G)P%KU`Lw}`aCRE9B3xNwVwY3?t3GzT zKloAzYQ5SOFB8_12h&DYIhSB%o80r#5)(T<^O<_GKlo<|Doxvb1{2nDBx+aBvy$2* z`_mE=YOgMezjUj$?flAwwbV8QI}K&O)6iIALj4B8Zbpe+wHaF`tffALV8>);zhlx^ zVnX8&k+txjbyhMUtR-83cpa8FT5q?+gzUI$WBzEp-GsH|1rX0uXURTJR#+NKOvoQ0 z-q`KqBx`a&SWCVMkzJYR);^#*iZQpu#7`AhI%0WZ$vs3k6V`H6YV#TDo7quJe!I1v zpIW8azt6uq`m&Xq-;MLHX0h)aVwY)zwe*A~YXIybAIHupYkid^CZ3;Kw%K`{f3-rl z@7%6mnXs06nl>(F7kOTv&tS=bn3}48GS0v1_nq7CK@)$MmMn%g?(H%l+IVG&iGNHz zQtvg+zhXCh=6Cyi1{2nj<POm{{zyH`bHLyvmCamR1M2;6kvJ=>qsVy;~_G&7TAX3@5?KHw# zY8zsuzOS-+XNd{*8^odz$^FQRmkDdB4C~8>=@!s zh=U>WR3@w?FMzh19;R-_tBOvoQ0j)O>sX{s|#SWCVMk$TZ&e`fv45)+OqUGyOj zIcrM;!di|o)Y?!5aU2=(`Q^0M`m^?J*68a8SJ-gRW~p)gV2D%-rS{c?we*B#Q9MKy z#CBx%X9i%2i8IgJy7`ZB{os9FrA3?1V8UAJY1*K6uzr*Zh2$DoV&d6FHfa7hsUL($ z<<@kj?g5ACWVJ%0Z zu8lbmsjjiagxaf%B5kCyF}q79tfi-g(3>}wm{7k#sCNg1wbX|YH!_0X=*GOU#DvBl zB9(xtG|h^a32Vs~ATGrcug4NITe8H2>=@!!h$kTuuS{4=UH~DFYAi7!e}qUCD;1jU z_n--D$u}WBN@O^e$dL1|EHUA@LX~Mx#7az9%Q2=XQb$HTS({B|E#_7Yn(g`(bE}5G z*5~_BZP-xjl^puggthd9B^B#<(~t40%$6)M!Q3kS*sotvYuQ{6krT5_SW7)k8^o$Q zRaIGAvcv>)tBh`+&wz#0socuk$AqVryC8^iv62B{E!hIZ6{3VnTKd@f(OMI%^*g z){;#_?1)EUS2;7YvBZS@5rX>N<{AjHkOqXc%kOvuR^={?*|SKZM9y zxCv{?VrYZ2Mapk86HmOd#Ki8;Z_zA1KL6@%5Z{GJOf+FFSw3y#6px&d($sKbMr9Ol> zv>)@#WGpeE@rTHl9qRyfqK^q{$rd0u9j30a#6&ntOvsKQa!wJa+~nI}Kv+vQ4Z(U$ zb0i*>FJVhe$R8nc_RhaSWc|v7wd9)+PZ1e*>S9T4i3!IQGU6e&gh-XC32QkjG2dl{ z^Zl%JX0OOv>zrJkmZtZHA$N@u?AEHS~}VDpOc`J$=odlVwE#DukEF|?5r{;p!B zGi_L6g1y0J{qgytSrhF~dm9kelI7FJM_A$f>(*zt^D9eCus7K3JU(CaP>7sCm)rEr9<*3x2VcKMWJKqM@BKN9c zC$UUE1G!fXyN&rb|1Hce^@`LGVu=I7T6#i=FSCQZ3p>g2C`(L`dzD?&{#?%UAnxJx z)_mibu$Fq7Htu5w`Dk{MGh4F61i4oYyT54XyuKSCWp z$Aqyt2fE>==U6zw2W<+Z_%sNKNX?i44m#f|i(YTq%lVyim=WSTZ22<)}p5J!4KYlWf3b0$PjQ_U7UKejIY! zo4dyMZhLdX_Xt$Zc=FJ-#0&S%AAhWVU3&TCy10pc1f5Jz1iUB__yiZ#Ep?k8?T1 zr4WgtCafjP@A|5mMW$Z*$`TXgwl}Mc@5f1H<|z=VT{2-Uc`$8o-$b<{nR@xfvBU(q z?ah)WjPAz?k<8-E!cADqk*I4UMDnjJF`@SA$y4P-QWMrv+Yov4lX>&h16X20{nitG z?+yrSsShE(HyOdk5)&GKh_6FX%^E8i5Z00{KycqgeO+g}jU^^z#}HRR9J&C)TC!<~ z)TF)?k4im`B_`yL5UH~~3?g5UCafjjgh(velvuJ7BWQ^U#}z6RARZ%@Y~>_bz<}BD>)xtfeP}h&^3RB}C>| zmYAS+u(^BvyVmRSMYAgSn{&Dwz)V<6Jxv=cQZunVl@N(nLy7k{Y9|umhLQM)AkL9Scm`m-%i;0PrEWhik>RnVq zB>D^`6N1{oX5K44+mA=)Ro{om|21JPc`$9{-lYSngvk8L5))=sr9=2_S9e9 z50Q9f!di|*)VTLV=2t_>a3-v!wjt6-S9X1s`*B7wyf&fnfJh&ucQa=& zVJ-C`L`HBC#vHrKZ8xLeA|&JS;NRo%=iiG%ysER3X~aZJ)&r4>t+P7YZHAHwAW?cgTKe4^5#Rygpfb>1h=KN_j#GHmV6T;^`d7H88YUUm~dR_ zV#$>dSpzU(EytLSNDX0TOAFBADLAXXn_uPM=;WTb&-T`C!diMl2&|;}R%a!-e{dZ8 zO!PfcckwE{`oK9e=O=5@#87M8)3lMB{$eGW$!Kg#6TL0)9*I{ALwufCl8h}AL#?sJ zKv3&kE`^mO`p8C06TMB(@7`l&h`(ZqxgW>GP-|@Yw2?R76f4P>uzaF4(RNbevu$UNXO(IbjuWs$ys232`+P|yz z&>1~dtlfmQ)HXVK^NYIQ!Q3V|is7{h^;=J*ck@+bVyHD94~SPVf=4idS-(>6=KjIN zu8ebPQZsKyJGTiEeag95Ng|wyq1M>0AaY~jsn~92WU`XM-<2IhtN<~q`yCt*L#?rY zKqOwpqvDIQ_EA)e-;E*$+6Di`2fx|<4h{%;ZSD*lc{4<6Qa{(ll7YlTAAQmW|4W4X zCIoghAck6#nbUYi*4`{HBY4OO{U? z>@-xbVqG+I2TM#G&;H=Ms3GjeBXyR`Kx9T{!dmiR+QwcS%iZ&VuACb+mrf64p}N5P9>L^XAzf zw8Vt^4I=C9%k`_yCak4Cgy8|0hx%Or6V{SVL!`oV34Ac~EK5wtA0aqlvsnm2D_*hc+FJ5Wh$UG)e~?&`j1)^u zIIeUn^ve@VwBp6zDQasu#*FhB+IVFxY6qz%ScRD&IdkM+9Yqac=O3JS+E7o{&d5wy zOHWwx%gN5@6YSB)qbxB&?O>br-}!m+8B%o^uQg#U^)zjKgB{*``dkA`Oi(-6JV$k4 z7q5~5vCtDwwlgvl){@202KNt^*Y+6@mYAS+kP3-M`gqkqoC}dJNE6nQ<vVg>wK`W#Dx42B2}ylcX=`c!dmi8h*W%qz;nIv*XFqCpEi=wxCdE!*%`IOM4#zcckwE>J01;@)7VT{OCC%c$rmlj(o43w zB_{fe%|2eG#w#_1{0ndjBnJ$?|EVuNZ0X!nVXjUrExBM_-ka%$iYtd)vCTUD^|qN=Ubv&4kPAAJaX!Ow)DU9F#i^Xnup~8v-S2sBmgAPOCbnzB zT6)5=C?4ajx8&`U18IqgTR5L#7itK*`PGvU-0;{|{hF|rdYU$oakeTi90x- zVQp#%yZP0F5Klm4@6Lp^WHGdn8ZV+;nKmpjaUbV1%%F~@dyl&zaN7Kct zPeB|6kuOLS)^a4`=Bx=Zss?QTmI<|251wj3SW9g~{FOJ)EtScBvBZS>4dQW#+#H$} zFB8^MA41&D2;R;JCNfxJLgNqdt%;Qk2y4j}Anw8ve~2aK3(^u3vSWzc!F%5V2y4lv zA+VBqQ#>kP!j_njKSHF=GPn1pcTHGJz6o(Mks%f9)On4n0b`@J3CEQ#`s9{MYGnq5 zwH#x*6CM7_JTA2v*6L4jNP9(pHbn0qd>1s_V&C3gXTn-~!jj)wW|iAAAI)i@mYC>I ztmysxV2FQ(h}W91mU@~txREUI-rzm*J(%-k`kUnjgtcTb5MSiWZX;&< ziC31G=+7MK-{VIRABM#^^v0bwomAq4jiwm1FVNi4C%gvK8t_gc>G#(Y3nOSS;P z2{d(T2otX?F(EsKxC>(c&e{irwd4g5|B6SYDmUlJSYkr{2yp^LY6!DJZ^BygO^E(% zs`kt?OH4SfbVR-)H)YICSj#bnc_Qm$StmOH+qG7IN>&@M`m?us|JV)UPKca`Y{FW4 z!m_(lk6N$x3_43p^e2M#e%_xh*5tf<6V_5s)5fi=K5|}PTUl(0iT*6KK3;ME;C${M zjFpVeziL~zmMn%g`jgn&^(#wE^e429;uY(ztn0U5kS44p%cl))$jgax?O9=#nCMTM z>&GK2&a92Lr?;B0mOPj?_G0Dy2G+wjX9O)V(Vwx`$E*JIy((FHCamR1#N7k5k-O-U zS!0O_wO5Z%5lrR%fUuU@hFFF-&u&99g)A|leuKy@e0}c@2y3YiA^H;++xe9xCN%yK z{i%*GBCI7_fZ+bY`QOA6Gl#QeKy>Ht#;zc+#GKccuZaO6Yp>-65S(pTX9Yd8B}+`m zA0b{1aS}w%Z#Q8r`6k3xM21_43|ldRmY8r{X)UqN$&p#{GGQ&pnD)-F_SUz|^sV(5 z&Tr@b!8Tr9$@%T;?*IATKRCCxUW%Q|tY4Y1mY%RAN0?pFWGEyb*%A{+bAJ2JsUhsX zqh9g95Y|#p)5dnG*kYGAYfF}x_#5Z9KS2#)H@{jPg7c7HL|97}LmR0!Oin}QSC*Lg z6X&-tMGay19_>yzM4rlowPg9U@n&}0M|U+^V&V|aZ$F3}qwag~wGgAzrcGE&9!wj* zC(mFZvIpM7m|J4vS@I9oriQT3XCTiYISp9@Fkvl6B392K3W!-)q9rEOUfteUm{XeD zcxA#`Y8zs8-u&xiDCEpcOH8QWAd>y?MTo3lnXs1n5JDq3IxVz~874IT5VDd1VJ+DL z#Cx&C2Rcg}ofaA!txd>|AvT8KJmhvp=D%evc>%->JSrIq*=exEg!~Z#yJ~O3ew_G3 z@mzO5PVXQ8N>$iF5bvEvSW8b>7R6`DI!pFhzV0kB@tf{`oZin*>xt~qo3NI8nl={M zY`giX!^&*Q5)*fjgS^x2S(D56Aol{yKOZ8|$AqUPM?+mQNcWA^(xet@i8A5)(UcKhD+EpLFr+-yk-ENbj1kmOPj?_NK<` z$TQ|t8FNcayp{WLPNasgi&q;!91c-VBdp~})ZI6cHa5m~Eis|?YEIJW+ekf*32W(T zA+VD6mdebpEHR;egE;zsA*`i7g!nUKo;=~Kg%B=421{+)R1 zb@3=mO!RjQ^?rT?L{7fQEiopnrJkmZ)2U9#U0aD)mYC@8O6ud)qY&Hx*2XIn){@20 z#uLoqUy)v+`bkk*&-&a zB@d>JPf{ndKNU9IN>W;4qQ6nAk5}Bgl)JXtJCRIS%aMrHL5Nh?WPi{S6Kbz6ihqYV z2qI^Tn6Q@GhWK&cSGfb!5)h=@!Qh*TY>4HMRqO+)ODM`c#IG5=X&LjDMGDnz~>vo~SF zTJlYZ!-)*s=heK85wygF<4RGS32_v}FRCG7EytMgjfKtg)%gCwHb(Wg6t@5FZ!+xt zqrWe;Y41zzZdHAemY%R=XA~>R4NA!=vc!M4zmc)`^H)M_1d*&s6V_5s)5h*t$xHg^ zV~L6WE=ry@^Q)^myUK6W=>EaBb!*9DAo`my+x06;O!PNo_V1DVQmGD$wO1yrCCjIc z+?Sfj!|&keHo^99ndoo&?8oCYh(x!nxBG8dOCC%cxi6JkulDQC5)=I$r+vKY?@MiW z6irymk!XBhYL(fNB_`BfJ-#os;+C-iVJ)={k$WvO1CK{pVnY1}@o|XcASYg#u$KA| zqQCLBjaQbK(D*~hN=7#pW&~?%$rd^yzk_YOvc!b!7~=RYini-lCafhdfY<?(?vG7IPa!RGD!)>`X6 z&c52YU%&biXI~}1zWe^j?R7Z^BI{QstfeO`xqF#ec`C!r5299j{+K1JU0THz2Gfi=mC%yIFV}eJn9?J!fB~ zZln7i9(%*wVUCN%yKUxAnp zfh7(IYsnTMF2NGd?Y{>tF(EsK_$>r?XV&>1G+`}y0mSxrRPJhIkA8Gpa~nlX$R8n& zfWQ))m%qN`Fv*u|?qK;-s1vhD|jwe*A~wPdVvX1zW021`sVbkIZP%!IYn)3k9oYvH-|E%C|{6R+WH(b?1xcJr$xAie>S^(zzBlEu(QzslKu-C1H{ z6V4WWiW^zMGW-GsGd`Lyv@swPuIn7*>a#BQ7|dJHv$-FQ$tSaTX%mA*1z zEqO3)JjJ>wtDMzhjG!eZ-ox3VIW@0azxp}E42YaSW5QaFMC9B-EDe!NKub)hy}G*z zGf%b5G{RbH8-msII;R!p%mGVGsNW!-qIXk6m<$LL)>0orY{LkqhA>}VmYC4^L&QpQ zvg35ZTCxR*R2z;~&n+<_JBHv4$eBD<`#osFTC!<~+`M=Z9+l{0i3#~5#0#9&_XUVV zI1|>AZ$jkcy`0&%J|k#}3CEQ#`lRYGV{XD)j!K+?&Av00TMe`D(ppnft5hGPhA{E! zSk7+$Ej5Ilf9wR2J;+o@o3NIiu*9y|Mb7D}@j**WOie9Y?L-Y>=jV%eJJl~Dtfii& zjq}JHIJ?hhu*AgF)D+buWMUNg9_0SPnVfc;->7OxOtfS%9Wnp1K0Cn@|J|vnN6OjM z5O(juZutC*7f4LBWcjqgj(hf<+u4#O{<||cyFK+M-FPelaR5Z_<}hI`c`$A4!oD+i z1Lj_U(h?I>Q%(8UtT*=YYF`LW&aT#;Mp(;{sI{v)ITPd|*Or)2d-de0$O;<}*3#2L zko!@m-ZCf3SziYm&W_S>KQtdr>W$hFBJlN={L}2QBg6l|Mq{Cd?xjKv+xO z46z51A?K^JD^puy!f}OaCy2Wsp5c4YgtZ)FxMH0wy;KBlfF)Y%``nH5u}89(#-0^- zq7|VJ%qeVpH(yC!m1BdZfU)g%sDOCC%c?SMk?H8m8Ysq>bE|^#%ZH%p?HX%EP z_$mZ;)y}U>SW8|2K?Zi~gUN5V#Dx420!u9Et0uR3n6Q?76Jit@nETY0m~dPv3T{2A za_2;{UQAfaF@}{p>Lzll&azmdwcfBjYO#F_!2cP2( z!ft+*yS%9NYU7m&Ysq40<8rDX9_wl|Doadk$K8W_a0g-c9$$mFxv$_cVJ%rcZ9Lpn zBDJgMmYBGcy9XcQ4#I9cZid*ct4gU%SW6yE8{Ed$Fy>Y6$Fao3CEPuD6?YJJ--8E3 zd;%hOBAKw3BM~PdKztH{Ib3at3AI7LLxy5V;-aH;S@}z0Sn>&!TjP>mYCR(yPa>OhOmoQ4?SXlys%oF=R#FMvpG`0wzj>`ho=LjDM` zGeqimvrlirTJlYZ+@j3XDP*Zo*oQF<3ma{EFE=x000B+V9h+ zR|^-bw(;sWKRK;BVSN4---6Xf5Nk~%tfeO`yL;k3#!Ni7b6H|yhXanGz2$m8&lk~t z5Sfvgu$Fq7HgfI1U+oRScTRi$l?iLf zgK2{?Z)P$R&zM_cf;+gXmlQwf<5h^%_hnbcgtZ)rx;A>Ew#0VnY1}u{#8(s^m1p0bwomAq3xo?U*MrSYkrs4^cwo4536g6V{R~KyW%t zP93U4SYkqU43V1DuXVONAgm>uhM*F#%9&1ySC*KNKSJcR9#(Sd_KIfEr8*c+@CJ7{#i=s^&xLd0uLSW7)k8(HD}BP*TRAGE~8 zo~ImGtu{Vi^h*$5hDaU3{@hu~fUuTqp(Dyv1SVctVnTKdk()5F#QB-SnXr~@ z8sbBERH|~ber1UX`6C2t?G+W8In!xCSWCVMF^UYCUs+zV8%C;C`og50a>4r&Oy_h=xtgh(4EtR>5*jpThi!A^3%?kq9ENxs$g)DU*#(N<=% zTb+6w6V{Rk(*`FGH;Yo=mphRxF~RA^)&2b$##F3B+|6z^xlsecT8>2BsoBYuNiL2h zCe$A9l6`IRCUUC$fUuUH7J^)c<`3O1m5n7P)Nc?u6?omQuLgv*)Q1rB8NpS$5o|0m zq49^f6=HVs4TvQstR-83;5NZ>Z!9s<#}X5=V~8sua1U?Q9eYv~Eg_T>8NNHX=3vu%lq zv#MCjoJ3r_C!78WY=fo@%)>2Q?#y82(+khIv#1czP>~i}F)mOWFOdvSrzub=8 zzI+dwu$C+aBH5*zP#u=&V~GiF7^vRR-J1fDdjWD=LE123Em=MUcPKRPAX6`q+7c7o zx=<}k4PiGPsmz=Uk=`|7EqO3)hA(CNg z!di|*%w!;T>)Oa^?Bm#HLhaS8UqLJnk$7doT5202Z_fRLdGnm#K6;Pbk2C6@++#Bu z4~S9k<_pqgRbXGDTtR-83xCl$U7E8?h$`TW@V+d*o z%VaMnUYW3#Y#JhWa~z6CW%b+=6Y@uhwISv}V2K05TJlW@MTVT;KAPjyCLC8L(I+eP zCamQc)7_#}Q=gHQ32TwrTP0TIf85$L`ghq8{{smMot(;(Ob7wG+8baO7)9CImN8X*@#o_rwhdYsrK8 zOR4@mlxn? + + + + + + + 0 0 1 + 0.1 0.2 + + + + + + + 0 0 1 + 0.1 0.2 + + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/geometry_plane/model.config b/sdformat_test_files/models/geometry_plane/model.config new file mode 100644 index 00000000..d398d533 --- /dev/null +++ b/sdformat_test_files/models/geometry_plane/model.config @@ -0,0 +1,15 @@ + + + geometry_plane + 1.0 + geometry_plane.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + A plane using only the plane geometry type for both the visual and collision and a color. + + diff --git a/sdformat_test_files/models/geometry_sphere/geometry_sphere.sdf b/sdformat_test_files/models/geometry_sphere/geometry_sphere.sdf new file mode 100644 index 00000000..ca3a256d --- /dev/null +++ b/sdformat_test_files/models/geometry_sphere/geometry_sphere.sdf @@ -0,0 +1,32 @@ + + + + + + + + 0.125 + + + + + + + 0.125 + + + + + 1.23 + + 0.0076875 + 0 + 0 + 0.0076875 + 0 + 0.0076875 + + + + + diff --git a/sdformat_test_files/models/geometry_sphere/model.config b/sdformat_test_files/models/geometry_sphere/model.config new file mode 100644 index 00000000..9f9a8e2d --- /dev/null +++ b/sdformat_test_files/models/geometry_sphere/model.config @@ -0,0 +1,15 @@ + + + geometry_sphere + 1.0 + geometry_sphere.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + A sphere using only the sphere geometry type for both the visual and collision and a color. + + diff --git a/sdformat_test_files/models/graph_chain/graph_chain.sdf b/sdformat_test_files/models/graph_chain/graph_chain.sdf new file mode 100644 index 00000000..97229672 --- /dev/null +++ b/sdformat_test_files/models/graph_chain/graph_chain.sdf @@ -0,0 +1,103 @@ + + + + + 0 0 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0 0.4 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + link_1 + link_2 + + 1 0 0 + + + + link_2 + link_3 + + 1 0 0 + + + + diff --git a/sdformat_test_files/models/graph_chain/model.config b/sdformat_test_files/models/graph_chain/model.config new file mode 100644 index 00000000..f59ae9f8 --- /dev/null +++ b/sdformat_test_files/models/graph_chain/model.config @@ -0,0 +1,14 @@ + + + graph_chain + 1.0 + graph_chain.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/graph_chain_non_canonical_root/graph_chain_non_canonical_root.sdf b/sdformat_test_files/models/graph_chain_non_canonical_root/graph_chain_non_canonical_root.sdf new file mode 100644 index 00000000..2dd43776 --- /dev/null +++ b/sdformat_test_files/models/graph_chain_non_canonical_root/graph_chain_non_canonical_root.sdf @@ -0,0 +1,103 @@ + + + + + 0 0 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0 0.4 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + link_2 + link_1 + + 1 0 0 + + + + link_3 + link_2 + + 1 0 0 + + + + diff --git a/sdformat_test_files/models/graph_chain_non_canonical_root/model.config b/sdformat_test_files/models/graph_chain_non_canonical_root/model.config new file mode 100644 index 00000000..3f14e419 --- /dev/null +++ b/sdformat_test_files/models/graph_chain_non_canonical_root/model.config @@ -0,0 +1,14 @@ + + + graph_chain_non_canonical_root + 1.0 + graph_chain_non_canonical_root.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/graph_four_bar/graph_four_bar.sdf b/sdformat_test_files/models/graph_four_bar/graph_four_bar.sdf new file mode 100644 index 00000000..2be3cf2e --- /dev/null +++ b/sdformat_test_files/models/graph_four_bar/graph_four_bar.sdf @@ -0,0 +1,146 @@ + + + + + 0 0 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.1 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.4 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.3 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + graph_four_bar_link_1 + graph_four_bar_link_2 + + 1 0 0 + + + + graph_four_bar_link_2 + graph_four_bar_link_3 + + 1 0 0 + + + + graph_four_bar_link_3 + graph_four_bar_link_4 + + 1 0 0 + + + + graph_four_bar_link_4 + graph_four_bar_link_1 + + 1 0 0 + + + + + diff --git a/sdformat_test_files/models/graph_four_bar/model.config b/sdformat_test_files/models/graph_four_bar/model.config new file mode 100644 index 00000000..72beaf1f --- /dev/null +++ b/sdformat_test_files/models/graph_four_bar/model.config @@ -0,0 +1,14 @@ + + + graph_four_bar + 1.0 + graph_four_bar.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/graph_loop/graph_loop.sdf b/sdformat_test_files/models/graph_loop/graph_loop.sdf new file mode 100644 index 00000000..a99db604 --- /dev/null +++ b/sdformat_test_files/models/graph_loop/graph_loop.sdf @@ -0,0 +1,110 @@ + + + + + 0 0.1 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.2 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + graph_loop_link_1 + graph_loop_link_2 + + 1 0 0 + + + + graph_loop_link_2 + graph_loop_link_3 + + 1 0 0 + + + + graph_loop_link_3 + graph_loop_link_1 + + 1 0 0 + + + + diff --git a/sdformat_test_files/models/graph_loop/model.config b/sdformat_test_files/models/graph_loop/model.config new file mode 100644 index 00000000..d1b69b5b --- /dev/null +++ b/sdformat_test_files/models/graph_loop/model.config @@ -0,0 +1,14 @@ + + + graph_loop + 1.0 + graph_loop.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/graph_tree/graph_tree.sdf b/sdformat_test_files/models/graph_tree/graph_tree.sdf new file mode 100644 index 00000000..f2b5b05d --- /dev/null +++ b/sdformat_test_files/models/graph_tree/graph_tree.sdf @@ -0,0 +1,208 @@ + + + + + 0 0.3 0.4 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.1 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.4 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.3 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.5 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + link_1 + link_2 + + 1 0 0 + + + + link_1 + link_3 + + 1 0 0 + + + + link_2 + link_4 + + 1 0 0 + + + + link_3 + link_5 + + 1 0 0 + + + + link_3 + link_6 + + 1 0 0 + + + + diff --git a/sdformat_test_files/models/graph_tree/model.config b/sdformat_test_files/models/graph_tree/model.config new file mode 100644 index 00000000..d05248b9 --- /dev/null +++ b/sdformat_test_files/models/graph_tree/model.config @@ -0,0 +1,14 @@ + + + graph_tree + 1.0 + graph_tree.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/graph_tree_non_canonical_root/graph_tree_non_canonical_root.sdf b/sdformat_test_files/models/graph_tree_non_canonical_root/graph_tree_non_canonical_root.sdf new file mode 100644 index 00000000..3988db97 --- /dev/null +++ b/sdformat_test_files/models/graph_tree_non_canonical_root/graph_tree_non_canonical_root.sdf @@ -0,0 +1,208 @@ + + + + + 0 0.4 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.1 0.2 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.3 0.4 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.3 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.5 0 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + link_3 + link_2 + + 1 0 0 + + + + link_3 + link_1 + + 1 0 0 + + + + link_2 + link_5 + + 1 0 0 + + + + link_1 + link_4 + + 1 0 0 + + + + link_1 + link_6 + + 1 0 0 + + + + diff --git a/sdformat_test_files/models/graph_tree_non_canonical_root/model.config b/sdformat_test_files/models/graph_tree_non_canonical_root/model.config new file mode 100644 index 00000000..0513776d --- /dev/null +++ b/sdformat_test_files/models/graph_tree_non_canonical_root/model.config @@ -0,0 +1,14 @@ + + + graph_tree_non_canonical_root + 1.0 + graph_tree_non_canonical_root.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/joint_ball/joint_ball.sdf b/sdformat_test_files/models/joint_ball/joint_ball.sdf new file mode 100644 index 00000000..cd00c496 --- /dev/null +++ b/sdformat_test_files/models/joint_ball/joint_ball.sdf @@ -0,0 +1,65 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + + link_1 + link_2 + + + diff --git a/sdformat_test_files/models/joint_ball/model.config b/sdformat_test_files/models/joint_ball/model.config new file mode 100644 index 00000000..798ad13b --- /dev/null +++ b/sdformat_test_files/models/joint_ball/model.config @@ -0,0 +1,15 @@ + + + joint_ball + 1.0 + joint_ball.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links with a ball joint between them. + + diff --git a/sdformat_test_files/models/joint_continuous/joint_continuous.sdf b/sdformat_test_files/models/joint_continuous/joint_continuous.sdf new file mode 100644 index 00000000..ce8bdff4 --- /dev/null +++ b/sdformat_test_files/models/joint_continuous/joint_continuous.sdf @@ -0,0 +1,68 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + link_1 + link_2 + + 1 0 0 + + + + diff --git a/sdformat_test_files/models/joint_continuous/model.config b/sdformat_test_files/models/joint_continuous/model.config new file mode 100644 index 00000000..ae44c7ec --- /dev/null +++ b/sdformat_test_files/models/joint_continuous/model.config @@ -0,0 +1,15 @@ + + + joint_continuous + 1.0 + joint_continuous.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links with a continuous joint between them. + + diff --git a/sdformat_test_files/models/joint_fixed/joint_fixed.sdf b/sdformat_test_files/models/joint_fixed/joint_fixed.sdf new file mode 100644 index 00000000..43573c38 --- /dev/null +++ b/sdformat_test_files/models/joint_fixed/joint_fixed.sdf @@ -0,0 +1,65 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + joint_fixed_link_1 + joint_fixed_link_2 + + + diff --git a/sdformat_test_files/models/joint_fixed/model.config b/sdformat_test_files/models/joint_fixed/model.config new file mode 100644 index 00000000..b5b0faff --- /dev/null +++ b/sdformat_test_files/models/joint_fixed/model.config @@ -0,0 +1,15 @@ + + + joint_fixed + 1.0 + joint_fixed.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links with a fixed joint between them. + + diff --git a/sdformat_test_files/models/joint_gearbox/joint_gearbox.sdf b/sdformat_test_files/models/joint_gearbox/joint_gearbox.sdf new file mode 100644 index 00000000..b6239421 --- /dev/null +++ b/sdformat_test_files/models/joint_gearbox/joint_gearbox.sdf @@ -0,0 +1,32 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/joint_gearbox/model.config b/sdformat_test_files/models/joint_gearbox/model.config new file mode 100644 index 00000000..0971c3b0 --- /dev/null +++ b/sdformat_test_files/models/joint_gearbox/model.config @@ -0,0 +1,15 @@ + + + joint_gearbox + 1.0 + joint_gearbox.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links connected to a reference link with revolute joints and a gearbox constraint. + + diff --git a/sdformat_test_files/models/joint_prismatic/joint_prismatic.sdf b/sdformat_test_files/models/joint_prismatic/joint_prismatic.sdf new file mode 100644 index 00000000..a4670b0a --- /dev/null +++ b/sdformat_test_files/models/joint_prismatic/joint_prismatic.sdf @@ -0,0 +1,72 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + joint_prismatic_link_1 + joint_prismatic_link_2 + + 0 1 0 + + -0.2 + 0.2 + + + + + diff --git a/sdformat_test_files/models/joint_prismatic/model.config b/sdformat_test_files/models/joint_prismatic/model.config new file mode 100644 index 00000000..f5407b43 --- /dev/null +++ b/sdformat_test_files/models/joint_prismatic/model.config @@ -0,0 +1,15 @@ + + + joint_prismatic + 1.0 + joint_prismatic.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links with a prismatic joint between them + + diff --git a/sdformat_test_files/models/joint_revolute/joint_revolute.sdf b/sdformat_test_files/models/joint_revolute/joint_revolute.sdf new file mode 100644 index 00000000..560167d3 --- /dev/null +++ b/sdformat_test_files/models/joint_revolute/joint_revolute.sdf @@ -0,0 +1,72 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + link_1 + link_2 + + 1 0 0 + + -1.5 + 1.5 + + + + + diff --git a/sdformat_test_files/models/joint_revolute/model.config b/sdformat_test_files/models/joint_revolute/model.config new file mode 100644 index 00000000..496f8bf6 --- /dev/null +++ b/sdformat_test_files/models/joint_revolute/model.config @@ -0,0 +1,15 @@ + + + joint_revolute + 1.0 + joint_revolute.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links with a revolute joint between them. + + diff --git a/sdformat_test_files/models/joint_revolute2/joint_revolute2.sdf b/sdformat_test_files/models/joint_revolute2/joint_revolute2.sdf new file mode 100644 index 00000000..aaa33050 --- /dev/null +++ b/sdformat_test_files/models/joint_revolute2/joint_revolute2.sdf @@ -0,0 +1,80 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + joint_revolute2_link_1 + joint_revolute2_link_2 + + 1 0 0 + + -1.5 + 1.5 + + + + + 0.707 0 0.707 + + -1.5 + 1.5 + + + + + diff --git a/sdformat_test_files/models/joint_revolute2/model.config b/sdformat_test_files/models/joint_revolute2/model.config new file mode 100644 index 00000000..ef017b7a --- /dev/null +++ b/sdformat_test_files/models/joint_revolute2/model.config @@ -0,0 +1,15 @@ + + + joint_revolute2 + 1.0 + joint_revolute2.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links with a revolute 2 joint between them. + + diff --git a/sdformat_test_files/models/joint_revolute_axis/joint_revolute_axis.sdf b/sdformat_test_files/models/joint_revolute_axis/joint_revolute_axis.sdf new file mode 100644 index 00000000..277de538 --- /dev/null +++ b/sdformat_test_files/models/joint_revolute_axis/joint_revolute_axis.sdf @@ -0,0 +1,72 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + link_1 + link_2 + + 0.1 1.23 4.567 + + -1.5 + 1.5 + + + + + diff --git a/sdformat_test_files/models/joint_revolute_axis/model.config b/sdformat_test_files/models/joint_revolute_axis/model.config new file mode 100644 index 00000000..a60370cc --- /dev/null +++ b/sdformat_test_files/models/joint_revolute_axis/model.config @@ -0,0 +1,14 @@ + + + joint_revolute_axis + 1.0 + joint_revolute_axis.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/joint_revolute_axis_in_frame/joint_revolute_axis_in_frame.sdf b/sdformat_test_files/models/joint_revolute_axis_in_frame/joint_revolute_axis_in_frame.sdf new file mode 100644 index 00000000..3cf3fe48 --- /dev/null +++ b/sdformat_test_files/models/joint_revolute_axis_in_frame/joint_revolute_axis_in_frame.sdf @@ -0,0 +1,75 @@ + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + link_1 + link_2 + + 0.1 1.23 4.567 + + -1.5 + 1.5 + + + + + diff --git a/sdformat_test_files/models/joint_revolute_axis_in_frame/model.config b/sdformat_test_files/models/joint_revolute_axis_in_frame/model.config new file mode 100644 index 00000000..5032f5df --- /dev/null +++ b/sdformat_test_files/models/joint_revolute_axis_in_frame/model.config @@ -0,0 +1,14 @@ + + + joint_revolute_axis_in_frame + 1.0 + joint_revolute_axis_in_frame.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/joint_revolute_default_limits/joint_revolute_default_limits.sdf b/sdformat_test_files/models/joint_revolute_default_limits/joint_revolute_default_limits.sdf new file mode 100644 index 00000000..69399b87 --- /dev/null +++ b/sdformat_test_files/models/joint_revolute_default_limits/joint_revolute_default_limits.sdf @@ -0,0 +1,68 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + link_1 + link_2 + + 1 0 0 + + + + diff --git a/sdformat_test_files/models/joint_revolute_default_limits/model.config b/sdformat_test_files/models/joint_revolute_default_limits/model.config new file mode 100644 index 00000000..eba0355a --- /dev/null +++ b/sdformat_test_files/models/joint_revolute_default_limits/model.config @@ -0,0 +1,14 @@ + + + joint_revolute_default_limits + 1.0 + joint_revolute_default_limits.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/joint_revolute_two_joints_two_links/joint_revolute_two_joints_two_links.sdf b/sdformat_test_files/models/joint_revolute_two_joints_two_links/joint_revolute_two_joints_two_links.sdf new file mode 100644 index 00000000..20fe45c2 --- /dev/null +++ b/sdformat_test_files/models/joint_revolute_two_joints_two_links/joint_revolute_two_joints_two_links.sdf @@ -0,0 +1,84 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + link_1 + link_2 + + 1 0 0 + + -1.5 + 1.5 + + + + + 0 0.1 0 0 0 0 + link_1 + link_2 + + 1 0 0 + + -1.5 + 1.5 + + + + + diff --git a/sdformat_test_files/models/joint_revolute_two_joints_two_links/model.config b/sdformat_test_files/models/joint_revolute_two_joints_two_links/model.config new file mode 100644 index 00000000..026a0a0a --- /dev/null +++ b/sdformat_test_files/models/joint_revolute_two_joints_two_links/model.config @@ -0,0 +1,14 @@ + + + joint_revolute_two_joints_two_links + 1.0 + joint_revolute_two_joints_two_links.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/joint_screw/joint_screw.sdf b/sdformat_test_files/models/joint_screw/joint_screw.sdf new file mode 100644 index 00000000..8f6c35e7 --- /dev/null +++ b/sdformat_test_files/models/joint_screw/joint_screw.sdf @@ -0,0 +1,73 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.2 0.3 + + + + + + + 0.1 0.2 0.3 + + + + + 1.23 + + 0.013325 + 0 + 0 + 0.01025 + 0 + 0.005125 + + + + + + joint_screw_link_1 + joint_screw_link_2 + + 0 0 1 + + -1.5 + 1.5 + + + 10 + + + diff --git a/sdformat_test_files/models/joint_screw/model.config b/sdformat_test_files/models/joint_screw/model.config new file mode 100644 index 00000000..e2b63451 --- /dev/null +++ b/sdformat_test_files/models/joint_screw/model.config @@ -0,0 +1,15 @@ + + + joint_screw + 1.0 + joint_screw.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links with a screw joint between them. + + diff --git a/sdformat_test_files/models/joint_universal/joint_universal.sdf b/sdformat_test_files/models/joint_universal/joint_universal.sdf new file mode 100644 index 00000000..9779d2d0 --- /dev/null +++ b/sdformat_test_files/models/joint_universal/joint_universal.sdf @@ -0,0 +1,66 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.17425 + 0 + 0.05125 + + + + + 0.1 0 0.1 0 0 0 + + + + 0.1 0.1 0.2 + + + + + + + 0.1 0.1 0.2 + + + + + 1.23 + + 0.005125 + 0 + 0 + 0.005125 + 0 + 0.00205 + + + + + + joint_universal_link_1 + joint_universal_link_2 + 0 0 0.1 0 0 0 + + + diff --git a/sdformat_test_files/models/joint_universal/model.config b/sdformat_test_files/models/joint_universal/model.config new file mode 100644 index 00000000..744fd61c --- /dev/null +++ b/sdformat_test_files/models/joint_universal/model.config @@ -0,0 +1,15 @@ + + + joint_universal + 1.0 + joint_universal.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two links with a universal joint between them. + + diff --git a/sdformat_test_files/models/link_inertia/link_inertia.sdf b/sdformat_test_files/models/link_inertia/link_inertia.sdf new file mode 100644 index 00000000..cb1298b3 --- /dev/null +++ b/sdformat_test_files/models/link_inertia/link_inertia.sdf @@ -0,0 +1,32 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 116.0 + + 5.652232699207 + -0.009719934438 + 1.293988226423 + 5.669473158652 + -0.007379583694 + 3.683196351726 + + + + + diff --git a/sdformat_test_files/models/link_inertia/model.config b/sdformat_test_files/models/link_inertia/model.config new file mode 100644 index 00000000..6dc6359b --- /dev/null +++ b/sdformat_test_files/models/link_inertia/model.config @@ -0,0 +1,14 @@ + + + link_inertia + 1.0 + link_inertia.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/link_light_point/link_light_point.sdf b/sdformat_test_files/models/link_light_point/link_light_point.sdf new file mode 100644 index 00000000..05ff17e3 --- /dev/null +++ b/sdformat_test_files/models/link_light_point/link_light_point.sdf @@ -0,0 +1,33 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + + diff --git a/sdformat_test_files/models/link_light_point/model.config b/sdformat_test_files/models/link_light_point/model.config new file mode 100644 index 00000000..c6200706 --- /dev/null +++ b/sdformat_test_files/models/link_light_point/model.config @@ -0,0 +1,14 @@ + + + link_light_point + 1.0 + link_light_point.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/link_multiple_collisions/link_multiple_collisions.sdf b/sdformat_test_files/models/link_multiple_collisions/link_multiple_collisions.sdf new file mode 100644 index 00000000..f9ad39ec --- /dev/null +++ b/sdformat_test_files/models/link_multiple_collisions/link_multiple_collisions.sdf @@ -0,0 +1,39 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.15 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/link_multiple_collisions/model.config b/sdformat_test_files/models/link_multiple_collisions/model.config new file mode 100644 index 00000000..2923b8d8 --- /dev/null +++ b/sdformat_test_files/models/link_multiple_collisions/model.config @@ -0,0 +1,14 @@ + + + link_multiple_collisions + 1.0 + link_multiple_collisions.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/link_multiple_visuals/link_multiple_visuals.sdf b/sdformat_test_files/models/link_multiple_visuals/link_multiple_visuals.sdf new file mode 100644 index 00000000..2c1123f9 --- /dev/null +++ b/sdformat_test_files/models/link_multiple_visuals/link_multiple_visuals.sdf @@ -0,0 +1,39 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.15 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/link_multiple_visuals/model.config b/sdformat_test_files/models/link_multiple_visuals/model.config new file mode 100644 index 00000000..6ccb0ce5 --- /dev/null +++ b/sdformat_test_files/models/link_multiple_visuals/model.config @@ -0,0 +1,14 @@ + + + link_multiple_visuals + 1.0 + link_multiple_visuals.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/link_sensor_imu/link_sensor_imu.sdf b/sdformat_test_files/models/link_sensor_imu/link_sensor_imu.sdf new file mode 100644 index 00000000..749c67f5 --- /dev/null +++ b/sdformat_test_files/models/link_sensor_imu/link_sensor_imu.sdf @@ -0,0 +1,35 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + + + + diff --git a/sdformat_test_files/models/link_sensor_imu/model.config b/sdformat_test_files/models/link_sensor_imu/model.config new file mode 100644 index 00000000..4123a292 --- /dev/null +++ b/sdformat_test_files/models/link_sensor_imu/model.config @@ -0,0 +1,14 @@ + + + link_sensor_imu + 1.0 + link_sensor_imu.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/material_blinn_phong/material_blinn_phong.sdf b/sdformat_test_files/models/material_blinn_phong/material_blinn_phong.sdf new file mode 100644 index 00000000..ac7aa6e5 --- /dev/null +++ b/sdformat_test_files/models/material_blinn_phong/material_blinn_phong.sdf @@ -0,0 +1,38 @@ + + + + + + + + 0.2 0.2 0.2 + + + + 0.3 0 0 1 + 0 0.3 0 1 + 0 0 0.3 1 + 0.1 0.1 0.1 1 + + + + + + 0.2 0.2 0.2 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/material_blinn_phong/model.config b/sdformat_test_files/models/material_blinn_phong/model.config new file mode 100644 index 00000000..3ae9e89a --- /dev/null +++ b/sdformat_test_files/models/material_blinn_phong/model.config @@ -0,0 +1,15 @@ + + + material_blinn_phong + 1.0 + material_blinn_phong.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Single link using ambient/diffuse/specular/emissive components to color it. + + diff --git a/sdformat_test_files/models/material_dynamic_lights/material_dynamic_lights.sdf b/sdformat_test_files/models/material_dynamic_lights/material_dynamic_lights.sdf new file mode 100644 index 00000000..0643fc8d --- /dev/null +++ b/sdformat_test_files/models/material_dynamic_lights/material_dynamic_lights.sdf @@ -0,0 +1,52 @@ + + + + + + + + 0.2 0.2 0.2 + + + + true + + + + + + 0.1 0.1 0.4 + + + + false + + + + + + 0.2 0.2 0.2 + + + + + + + 0.1 0.1 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/material_dynamic_lights/model.config b/sdformat_test_files/models/material_dynamic_lights/model.config new file mode 100644 index 00000000..66a1a865 --- /dev/null +++ b/sdformat_test_files/models/material_dynamic_lights/model.config @@ -0,0 +1,15 @@ + + + material_dynamic_lights + 1.0 + material_dynamic_lights.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + Two visuals: one with dynamic lights on, another with dynamic lights off. + + diff --git a/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf b/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf new file mode 100644 index 00000000..a9487c77 --- /dev/null +++ b/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf @@ -0,0 +1,32 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/material_ogre_script/model.config b/sdformat_test_files/models/material_ogre_script/model.config new file mode 100644 index 00000000..09634739 --- /dev/null +++ b/sdformat_test_files/models/material_ogre_script/model.config @@ -0,0 +1,14 @@ + + + material_ogre_script + 1.0 + material_ogre_script.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/material_pbr/material_pbr.sdf b/sdformat_test_files/models/material_pbr/material_pbr.sdf new file mode 100644 index 00000000..69242ba5 --- /dev/null +++ b/sdformat_test_files/models/material_pbr/material_pbr.sdf @@ -0,0 +1,32 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/material_pbr/model.config b/sdformat_test_files/models/material_pbr/model.config new file mode 100644 index 00000000..ca5b1aa3 --- /dev/null +++ b/sdformat_test_files/models/material_pbr/model.config @@ -0,0 +1,14 @@ + + + material_pbr + 1.0 + material_pbr.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/material_shader/material_shader.sdf b/sdformat_test_files/models/material_shader/material_shader.sdf new file mode 100644 index 00000000..0abd442e --- /dev/null +++ b/sdformat_test_files/models/material_shader/material_shader.sdf @@ -0,0 +1,32 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/material_shader/model.config b/sdformat_test_files/models/material_shader/model.config new file mode 100644 index 00000000..4148e8d7 --- /dev/null +++ b/sdformat_test_files/models/material_shader/model.config @@ -0,0 +1,14 @@ + + + material_shader + 1.0 + material_shader.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/model_two_models/model.config b/sdformat_test_files/models/model_two_models/model.config new file mode 100644 index 00000000..05bbe2c6 --- /dev/null +++ b/sdformat_test_files/models/model_two_models/model.config @@ -0,0 +1,14 @@ + + + model_two_models + 1.0 + model_two_models.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/model_two_models/model_two_models.sdf b/sdformat_test_files/models/model_two_models/model_two_models.sdf new file mode 100644 index 00000000..b6e3b405 --- /dev/null +++ b/sdformat_test_files/models/model_two_models/model_two_models.sdf @@ -0,0 +1,61 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + + + + + + 0.125 + + + + + + + 0.125 + + + + + 1.23 + + 0.0076875 + 0 + 0 + 0.0076875 + 0 + 0.0076875 + + + + + diff --git a/sdformat_test_files/models/model_zero_models/model.config b/sdformat_test_files/models/model_zero_models/model.config new file mode 100644 index 00000000..da3fa4c7 --- /dev/null +++ b/sdformat_test_files/models/model_zero_models/model.config @@ -0,0 +1,14 @@ + + + model_zero_models + 1.0 + model_zero_models.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/model_zero_models/model_zero_models.sdf b/sdformat_test_files/models/model_zero_models/model_zero_models.sdf new file mode 100644 index 00000000..763666a0 --- /dev/null +++ b/sdformat_test_files/models/model_zero_models/model_zero_models.sdf @@ -0,0 +1,3 @@ + + + diff --git a/sdformat_test_files/models/pose_chain/model.config b/sdformat_test_files/models/pose_chain/model.config new file mode 100644 index 00000000..58337375 --- /dev/null +++ b/sdformat_test_files/models/pose_chain/model.config @@ -0,0 +1,14 @@ + + + pose_chain + 1.0 + pose_chain.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_chain/pose_chain.sdf b/sdformat_test_files/models/pose_chain/pose_chain.sdf new file mode 100644 index 00000000..800b6405 --- /dev/null +++ b/sdformat_test_files/models/pose_chain/pose_chain.sdf @@ -0,0 +1,153 @@ + + + + + 0.1 0.2 0.3 0.4 0.5 0.6 + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + 0.2 0.3 0.4 0.5 0.6 0.7 + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + 0.3 0.4 0.5 0.6 0.7 0.8 + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + 0.4 0.5 0.6 0.7 0.8 0.9 + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + 0.9 0.8 0.7 0.6 0.5 0.4 + pose_chain_link_1 + pose_chain_link_2 + + 1 0 0 + + -1.5 + 1.5 + + + + + 0.8 0.7 0.6 0.5 0.4 0.3 + pose_chain_link_2 + pose_chain_link_3 + + 1 0 0 + + -1.5 + 1.5 + + + + + 0.7 0.6 0.5 0.4 0.3 0.2 + pose_chain_link_3 + pose_chain_link_4 + + 1 0 0 + + -1.5 + 1.5 + + + + + diff --git a/sdformat_test_files/models/pose_collision/model.config b/sdformat_test_files/models/pose_collision/model.config new file mode 100644 index 00000000..f38bb20a --- /dev/null +++ b/sdformat_test_files/models/pose_collision/model.config @@ -0,0 +1,14 @@ + + + pose_collision + 1.0 + pose_collision.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_collision/pose_collision.sdf b/sdformat_test_files/models/pose_collision/pose_collision.sdf new file mode 100644 index 00000000..34533269 --- /dev/null +++ b/sdformat_test_files/models/pose_collision/pose_collision.sdf @@ -0,0 +1,33 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_collision_in_frame/model.config b/sdformat_test_files/models/pose_collision_in_frame/model.config new file mode 100644 index 00000000..86c7e88f --- /dev/null +++ b/sdformat_test_files/models/pose_collision_in_frame/model.config @@ -0,0 +1,14 @@ + + + pose_collision_in_frame + 1.0 + pose_collision_in_frame.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_collision_in_frame/pose_collision_in_frame.sdf b/sdformat_test_files/models/pose_collision_in_frame/pose_collision_in_frame.sdf new file mode 100644 index 00000000..4dc1ad57 --- /dev/null +++ b/sdformat_test_files/models/pose_collision_in_frame/pose_collision_in_frame.sdf @@ -0,0 +1,36 @@ + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + + + + 0.1 0.2 0.4 + + + + + 0.2 0.4 0.8 0.2 0.3 0.4 + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_inertial/model.config b/sdformat_test_files/models/pose_inertial/model.config new file mode 100644 index 00000000..0fdd7ab2 --- /dev/null +++ b/sdformat_test_files/models/pose_inertial/model.config @@ -0,0 +1,14 @@ + + + pose_inertial + 1.0 + pose_inertial.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_inertial/pose_inertial.sdf b/sdformat_test_files/models/pose_inertial/pose_inertial.sdf new file mode 100644 index 00000000..6ea8f73f --- /dev/null +++ b/sdformat_test_files/models/pose_inertial/pose_inertial.sdf @@ -0,0 +1,33 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_inertial_in_frame/model.config b/sdformat_test_files/models/pose_inertial_in_frame/model.config new file mode 100644 index 00000000..e383183e --- /dev/null +++ b/sdformat_test_files/models/pose_inertial_in_frame/model.config @@ -0,0 +1,14 @@ + + + pose_inertial_in_frame + 1.0 + pose_inertial_in_frame.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_inertial_in_frame/pose_inertial_in_frame.sdf b/sdformat_test_files/models/pose_inertial_in_frame/pose_inertial_in_frame.sdf new file mode 100644 index 00000000..5e1b309d --- /dev/null +++ b/sdformat_test_files/models/pose_inertial_in_frame/pose_inertial_in_frame.sdf @@ -0,0 +1,36 @@ + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 0.2 0.4 0.8 0.2 0.3 0.4 + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_joint/model.config b/sdformat_test_files/models/pose_joint/model.config new file mode 100644 index 00000000..8b43f0b1 --- /dev/null +++ b/sdformat_test_files/models/pose_joint/model.config @@ -0,0 +1,14 @@ + + + pose_joint + 1.0 + pose_joint.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_joint/pose_joint.sdf b/sdformat_test_files/models/pose_joint/pose_joint.sdf new file mode 100644 index 00000000..1e62e036 --- /dev/null +++ b/sdformat_test_files/models/pose_joint/pose_joint.sdf @@ -0,0 +1,71 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + pose_joint_link_1 + pose_joint_link_2 + + 1 0 0 + + -1.5 + 1.5 + + + + + diff --git a/sdformat_test_files/models/pose_joint_in_frame/model.config b/sdformat_test_files/models/pose_joint_in_frame/model.config new file mode 100644 index 00000000..45e04007 --- /dev/null +++ b/sdformat_test_files/models/pose_joint_in_frame/model.config @@ -0,0 +1,14 @@ + + + pose_joint_in_frame + 1.0 + pose_joint_in_frame.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_joint_in_frame/pose_joint_in_frame.sdf b/sdformat_test_files/models/pose_joint_in_frame/pose_joint_in_frame.sdf new file mode 100644 index 00000000..64950bca --- /dev/null +++ b/sdformat_test_files/models/pose_joint_in_frame/pose_joint_in_frame.sdf @@ -0,0 +1,74 @@ + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + pose_joint_in_frame_link_1 + pose_joint_in_frame_link_2 + + 1 0 0 + + -1.5 + 1.5 + + + + + diff --git a/sdformat_test_files/models/pose_link/model.config b/sdformat_test_files/models/pose_link/model.config new file mode 100644 index 00000000..68368ef8 --- /dev/null +++ b/sdformat_test_files/models/pose_link/model.config @@ -0,0 +1,14 @@ + + + pose_link + 1.0 + pose_link.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_link/pose_link.sdf b/sdformat_test_files/models/pose_link/pose_link.sdf new file mode 100644 index 00000000..a110b565 --- /dev/null +++ b/sdformat_test_files/models/pose_link/pose_link.sdf @@ -0,0 +1,33 @@ + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_link_all/model.config b/sdformat_test_files/models/pose_link_all/model.config new file mode 100644 index 00000000..a637e8df --- /dev/null +++ b/sdformat_test_files/models/pose_link_all/model.config @@ -0,0 +1,14 @@ + + + pose_link_all + 1.0 + pose_link_all.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_link_all/pose_link_all.sdf b/sdformat_test_files/models/pose_link_all/pose_link_all.sdf new file mode 100644 index 00000000..65e90062 --- /dev/null +++ b/sdformat_test_files/models/pose_link_all/pose_link_all.sdf @@ -0,0 +1,36 @@ + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + 0.03 0.6 0.12 0.2 0.3 0.4 + + + 0.1 0.2 0.4 + + + + + 0.04 0.8 0.16 0.3 0.4 0.5 + + + 0.1 0.2 0.4 + + + + + 0.05 0.1 0.2 0.4 0.5 0.6 + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_link_in_frame/model.config b/sdformat_test_files/models/pose_link_in_frame/model.config new file mode 100644 index 00000000..eb811cfa --- /dev/null +++ b/sdformat_test_files/models/pose_link_in_frame/model.config @@ -0,0 +1,14 @@ + + + pose_link_in_frame + 1.0 + pose_link_in_frame.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_link_in_frame/pose_link_in_frame.sdf b/sdformat_test_files/models/pose_link_in_frame/pose_link_in_frame.sdf new file mode 100644 index 00000000..29b8b6fb --- /dev/null +++ b/sdformat_test_files/models/pose_link_in_frame/pose_link_in_frame.sdf @@ -0,0 +1,36 @@ + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + 0.2 0.4 0.8 0.2 0.3 0.4 + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_model/model.config b/sdformat_test_files/models/pose_model/model.config new file mode 100644 index 00000000..c500ee24 --- /dev/null +++ b/sdformat_test_files/models/pose_model/model.config @@ -0,0 +1,14 @@ + + + pose_model + 1.0 + pose_model.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_model/pose_model.sdf b/sdformat_test_files/models/pose_model/pose_model.sdf new file mode 100644 index 00000000..e65b2f79 --- /dev/null +++ b/sdformat_test_files/models/pose_model/pose_model.sdf @@ -0,0 +1,33 @@ + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_visual/model.config b/sdformat_test_files/models/pose_visual/model.config new file mode 100644 index 00000000..a2186fa5 --- /dev/null +++ b/sdformat_test_files/models/pose_visual/model.config @@ -0,0 +1,14 @@ + + + pose_visual + 1.0 + pose_visual.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_visual/pose_visual.sdf b/sdformat_test_files/models/pose_visual/pose_visual.sdf new file mode 100644 index 00000000..09eaf128 --- /dev/null +++ b/sdformat_test_files/models/pose_visual/pose_visual.sdf @@ -0,0 +1,33 @@ + + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_visual_in_frame/model.config b/sdformat_test_files/models/pose_visual_in_frame/model.config new file mode 100644 index 00000000..d57d05a9 --- /dev/null +++ b/sdformat_test_files/models/pose_visual_in_frame/model.config @@ -0,0 +1,14 @@ + + + pose_visual_in_frame + 1.0 + pose_visual_in_frame.sdf + + + Shane Loretz + sloretz@openrobotics.org + + + + + diff --git a/sdformat_test_files/models/pose_visual_in_frame/pose_visual_in_frame.sdf b/sdformat_test_files/models/pose_visual_in_frame/pose_visual_in_frame.sdf new file mode 100644 index 00000000..86eab968 --- /dev/null +++ b/sdformat_test_files/models/pose_visual_in_frame/pose_visual_in_frame.sdf @@ -0,0 +1,36 @@ + + + + + 0.05 0.1 0.2 0.1 0.2 0.3 + + + + 0.2 0.4 0.8 0.2 0.3 0.4 + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/package.xml b/sdformat_test_files/package.xml new file mode 100644 index 00000000..76cfee60 --- /dev/null +++ b/sdformat_test_files/package.xml @@ -0,0 +1,23 @@ + + + sdformat_test_files + 0.1.0 + + Example SDFormat XML files for testing tools using hthis format. + + + Shane Loretz + Shane Loretz + + Apache 2.0 + + https://github.com/ros/sdformat_test_files + https://github.com/ros/sdformat_test_files/issues + + cmake + cmake + + + cmake + + diff --git a/sdformat_test_files/sdformat_test_filesConfig.cmake.in b/sdformat_test_files/sdformat_test_filesConfig.cmake.in new file mode 100644 index 00000000..b74b7626 --- /dev/null +++ b/sdformat_test_files/sdformat_test_filesConfig.cmake.in @@ -0,0 +1,7 @@ +@PACKAGE_INIT@ + +set_and_check(sdformat_test_files_MODELS_DIR "@PACKAGE_INSTALL_SHARE_DIR@/models") + +include("@PACKAGE_INSTALL_CMAKE_DIR@/sdformat_test_files_functions.cmake") + +check_required_components("sdformat_test_files") diff --git a/sdformat_test_files/sdformat_test_files_functions.cmake.in b/sdformat_test_files/sdformat_test_files_functions.cmake.in new file mode 100644 index 00000000..e6b21596 --- /dev/null +++ b/sdformat_test_files/sdformat_test_files_functions.cmake.in @@ -0,0 +1,32 @@ +# This file assumes sdformat_test_files_MODELS_DIR exists + +function(sdformat_test_files_has_model arg model_name) + set(known_model_names @model_names@) + foreach(known_model_name ${model_names}) + if("${model_name}" STREQUAL "${known_model_name") + set("${arg}" TRUE PARENT_SCOPE) + return() + endif() + endforeach() + set("${arg}" "${model_name}-NOTFOUND}" PARENT_SCOPE) +endfunction() + +# Get path to directory containing model.config for a model with the given name +function(sdformat_test_files_get_model_path arg model_name) + sdformat_test_files_has_model("has_model" "${model_name}") + if(NOT has_model) + message(FATAL_ERROR "Unknown model ${model_name}") + endif() + + set("${arg}" "${sdformat_test_files_MODELS_DIR}/${model_name}" PARENT_SCOPE) +endfunction() + +# Get path to .sdf for a model with the given name +function(sdformat_test_files_get_model_sdf arg model_name) + sdformat_test_files_has_model("has_model" "${model_name}") + if(NOT has_model) + message(FATAL_ERROR "Unknown model ${model_name}") + endif() + + set("${arg}" "${sdformat_test_files_MODELS_DIR}/${model_name}/${model_name}.sdf" PARENT_SCOPE) +endfunction() From f7fcfe55eee5cf4d6370c080c5fbe87125aab973 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 18:13:09 -0700 Subject: [PATCH 106/152] lilnk -> link Signed-off-by: Shane Loretz --- sdformat_urdf/src/sdformat_urdf.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sdformat_urdf/src/sdformat_urdf.cpp b/sdformat_urdf/src/sdformat_urdf.cpp index 8552a0f8..d0905042 100644 --- a/sdformat_urdf/src/sdformat_urdf.cpp +++ b/sdformat_urdf/src/sdformat_urdf.cpp @@ -357,7 +357,7 @@ sdformat_urdf::convert_link( if (!sdf_visual) { errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get visual on lilnk [" + sdf_link.Name() + "]"); + "Failed to get visual on link [" + sdf_link.Name() + "]"); return nullptr; } @@ -414,7 +414,7 @@ sdformat_urdf::convert_link( if (!sdf_collision) { errors.emplace_back( sdf::ErrorCode::STRING_READ, - "Failed to get collision on lilnk [" + sdf_link.Name() + "]"); + "Failed to get collision on link [" + sdf_link.Name() + "]"); return nullptr; } From 135cb9061531e93ce60e7b63ae59ba718c1b8895 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 18:14:48 -0700 Subject: [PATCH 107/152] Whitespace Signed-off-by: Shane Loretz --- sdformat_urdf/src/sdformat_urdf.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/sdformat_urdf/src/sdformat_urdf.cpp b/sdformat_urdf/src/sdformat_urdf.cpp index d0905042..55748c8f 100644 --- a/sdformat_urdf/src/sdformat_urdf.cpp +++ b/sdformat_urdf/src/sdformat_urdf.cpp @@ -57,7 +57,6 @@ sdformat_urdf::parse(const std::string & data, sdf::Errors & errors) return nullptr; } - urdf::ModelInterfaceSharedPtr sdformat_urdf::sdf_to_urdf(const sdf::Root & sdf_dom, sdf::Errors & errors) { @@ -557,7 +556,6 @@ sdformat_urdf::convert_joint(const sdf::Joint & sdf_joint, sdf::Errors & errors) } } - urdf_joint->child_link_name = sdf_joint.ChildLinkName(); urdf_joint->parent_link_name = sdf_joint.ParentLinkName(); From c9ca57183c0c3dde127fb05b34256a6705edb01b Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 18:40:40 -0700 Subject: [PATCH 108/152] Save a line Signed-off-by: Shane Loretz --- sdformat_urdf/src/sdformat_urdf_plugin.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/sdformat_urdf/src/sdformat_urdf_plugin.cpp b/sdformat_urdf/src/sdformat_urdf_plugin.cpp index c49d5d22..aa2f2e0c 100644 --- a/sdformat_urdf/src/sdformat_urdf_plugin.cpp +++ b/sdformat_urdf/src/sdformat_urdf_plugin.cpp @@ -32,9 +32,8 @@ class SDFormatURDFParser final : public urdf::URDFParser urdf::ModelInterfaceSharedPtr parse(const std::string & data) override { - urdf::ModelInterfaceSharedPtr urdf_cpp; sdf::Errors errors; - urdf_cpp = sdformat_urdf::parse(data, errors); + urdf::ModelInterfaceSharedPtr urdf_cpp = sdformat_urdf::parse(data, errors); if (urdf_cpp) { return urdf_cpp; From 44763d4855044ff4d73897507aa9e1185a23eb71 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 18:43:31 -0700 Subject: [PATCH 109/152] Move PlaneShape check lower Signed-off-by: Shane Loretz --- sdformat_urdf/src/sdformat_urdf.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/sdformat_urdf/src/sdformat_urdf.cpp b/sdformat_urdf/src/sdformat_urdf.cpp index 55748c8f..b6902d52 100644 --- a/sdformat_urdf/src/sdformat_urdf.cpp +++ b/sdformat_urdf/src/sdformat_urdf.cpp @@ -599,11 +599,6 @@ sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors auto urdf_sphere = std::make_shared(); urdf_sphere->radius = sphere->Radius(); return urdf_sphere; - } else if (sdf_geometry.PlaneShape()) { - errors.emplace_back( - sdf::ErrorCode::STRING_READ, - "Plane geometry cannot be converted to urdf C++ structures"); - return nullptr; } else if (sdf_geometry.MeshShape()) { const std::string & uri = sdf_geometry.MeshShape()->Uri(); auto urdf_mesh = std::make_shared(); @@ -618,6 +613,11 @@ sdformat_urdf::convert_geometry(const sdf::Geometry & sdf_geometry, sdf::Errors urdf_mesh->scale.y = sdf_geometry.MeshShape()->Scale().Y(); urdf_mesh->scale.z = sdf_geometry.MeshShape()->Scale().Z(); return urdf_mesh; + } else if (sdf_geometry.PlaneShape()) { + errors.emplace_back( + sdf::ErrorCode::STRING_READ, + "Plane geometry cannot be converted to urdf C++ structures"); + return nullptr; } errors.emplace_back( From 0dd8103082407d8af0c6de151f0a6199920c97bf Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 8 Oct 2020 18:46:37 -0700 Subject: [PATCH 110/152] Remove impossible condition after make_shared Signed-off-by: Shane Loretz --- sdformat_urdf/src/sdformat_urdf.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/sdformat_urdf/src/sdformat_urdf.cpp b/sdformat_urdf/src/sdformat_urdf.cpp index b6902d52..b0c30597 100644 --- a/sdformat_urdf/src/sdformat_urdf.cpp +++ b/sdformat_urdf/src/sdformat_urdf.cpp @@ -335,12 +335,6 @@ sdformat_urdf::convert_link( const ignition::math::Inertiald sdf_inertia = sdf_link.Inertial(); urdf_link->inertial = std::make_shared(); - if (!urdf_link->inertial) { - errors.emplace_back( - sdf::ErrorCode::STRING_READ, - "Failed to create inertial for link [" + sdf_link.Name() + "]"); - return nullptr; - } urdf_link->inertial->mass = sdf_inertia.MassMatrix().Mass(); // URDF doesn't have link pose concept, so add SDF link pose to inertial urdf_link->inertial->origin = convert_pose(link_pose + sdf_inertia.Pose()); From 2ac36ec381c35268c2a163c637b84dfff5efedb2 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 9 Oct 2020 07:44:48 -0700 Subject: [PATCH 111/152] Make names shorter Signed-off-by: Shane Loretz --- .../models/geometry_box/geometry_box.sdf | 6 +-- .../geometry_cylinder/geometry_cylinder.sdf | 6 +-- .../geometry_heightmap/geometry_heightmap.sdf | 6 +-- .../geometry_mesh_collada.sdf | 6 +-- .../geometry_mesh_obj/geometry_mesh_obj.sdf | 6 +-- .../geometry_mesh_stl/geometry_mesh_stl.sdf | 6 +-- .../models/geometry_plane/geometry_plane.sdf | 6 +-- .../geometry_sphere/geometry_sphere.sdf | 6 +-- .../models/graph_four_bar/graph_four_bar.sdf | 40 +++++++++---------- .../models/graph_loop/graph_loop.sdf | 30 +++++++------- .../models/joint_fixed/joint_fixed.sdf | 16 ++++---- .../joint_prismatic/joint_prismatic.sdf | 16 ++++---- .../joint_revolute2/joint_revolute2.sdf | 16 ++++---- .../models/joint_screw/joint_screw.sdf | 16 ++++---- .../joint_universal/joint_universal.sdf | 16 ++++---- .../material_blinn_phong.sdf | 6 +-- .../material_dynamic_lights.sdf | 10 ++--- .../material_ogre_script.sdf | 6 +-- .../models/material_pbr/material_pbr.sdf | 6 +-- .../material_shader/material_shader.sdf | 6 +-- sdformat_test_files/models/model.sdf | 32 +++++++++++++++ .../models/pose_chain/pose_chain.sdf | 36 ++++++++--------- .../models/pose_collision/pose_collision.sdf | 6 +-- .../pose_collision_in_frame.sdf | 6 +-- .../models/pose_inertial/pose_inertial.sdf | 6 +-- .../pose_inertial_in_frame.sdf | 6 +-- .../models/pose_joint/pose_joint.sdf | 16 ++++---- .../pose_joint_in_frame.sdf | 16 ++++---- .../models/pose_link/pose_link.sdf | 6 +-- .../models/pose_link_all/pose_link_all.sdf | 6 +-- .../pose_link_in_frame/pose_link_in_frame.sdf | 6 +-- .../models/pose_model/pose_model.sdf | 6 +-- .../models/pose_visual/pose_visual.sdf | 6 +-- .../pose_visual_in_frame.sdf | 6 +-- sdformat_urdf/test/pose_tests.cpp | 8 ++-- 35 files changed, 216 insertions(+), 184 deletions(-) create mode 100644 sdformat_test_files/models/model.sdf diff --git a/sdformat_test_files/models/geometry_box/geometry_box.sdf b/sdformat_test_files/models/geometry_box/geometry_box.sdf index 80d3f478..b8181828 100644 --- a/sdformat_test_files/models/geometry_box/geometry_box.sdf +++ b/sdformat_test_files/models/geometry_box/geometry_box.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/geometry_cylinder/geometry_cylinder.sdf b/sdformat_test_files/models/geometry_cylinder/geometry_cylinder.sdf index 91213e74..feab1f23 100644 --- a/sdformat_test_files/models/geometry_cylinder/geometry_cylinder.sdf +++ b/sdformat_test_files/models/geometry_cylinder/geometry_cylinder.sdf @@ -1,8 +1,8 @@ - - + + 0.2 @@ -10,7 +10,7 @@ - + 0.2 diff --git a/sdformat_test_files/models/geometry_heightmap/geometry_heightmap.sdf b/sdformat_test_files/models/geometry_heightmap/geometry_heightmap.sdf index ee183381..fd506ed4 100644 --- a/sdformat_test_files/models/geometry_heightmap/geometry_heightmap.sdf +++ b/sdformat_test_files/models/geometry_heightmap/geometry_heightmap.sdf @@ -1,8 +1,8 @@ - - + + heightmap.png @@ -10,7 +10,7 @@ - + heightmap.png diff --git a/sdformat_test_files/models/geometry_mesh_collada/geometry_mesh_collada.sdf b/sdformat_test_files/models/geometry_mesh_collada/geometry_mesh_collada.sdf index 4b1fa500..d50c63b7 100644 --- a/sdformat_test_files/models/geometry_mesh_collada/geometry_mesh_collada.sdf +++ b/sdformat_test_files/models/geometry_mesh_collada/geometry_mesh_collada.sdf @@ -1,8 +1,8 @@ - - + + model://geometry_mesh_collada/torus.dae @@ -10,7 +10,7 @@ - + model://geometry_mesh_collada/torus.dae diff --git a/sdformat_test_files/models/geometry_mesh_obj/geometry_mesh_obj.sdf b/sdformat_test_files/models/geometry_mesh_obj/geometry_mesh_obj.sdf index e4757b08..e456e50b 100644 --- a/sdformat_test_files/models/geometry_mesh_obj/geometry_mesh_obj.sdf +++ b/sdformat_test_files/models/geometry_mesh_obj/geometry_mesh_obj.sdf @@ -1,8 +1,8 @@ - - + + model://geometry_mesh_obj/torus.obj @@ -10,7 +10,7 @@ - + model://geometry_mesh_obj/torus.obj diff --git a/sdformat_test_files/models/geometry_mesh_stl/geometry_mesh_stl.sdf b/sdformat_test_files/models/geometry_mesh_stl/geometry_mesh_stl.sdf index 50646049..0c3f4534 100644 --- a/sdformat_test_files/models/geometry_mesh_stl/geometry_mesh_stl.sdf +++ b/sdformat_test_files/models/geometry_mesh_stl/geometry_mesh_stl.sdf @@ -1,8 +1,8 @@ - - + + model://geometry_mesh_stl/torus.stl @@ -10,7 +10,7 @@ - + model://geometry_mesh_stl/torus.stl diff --git a/sdformat_test_files/models/geometry_plane/geometry_plane.sdf b/sdformat_test_files/models/geometry_plane/geometry_plane.sdf index a8f47e00..b9f0d822 100644 --- a/sdformat_test_files/models/geometry_plane/geometry_plane.sdf +++ b/sdformat_test_files/models/geometry_plane/geometry_plane.sdf @@ -1,8 +1,8 @@ - - + + 0 0 1 @@ -10,7 +10,7 @@ - + 0 0 1 diff --git a/sdformat_test_files/models/geometry_sphere/geometry_sphere.sdf b/sdformat_test_files/models/geometry_sphere/geometry_sphere.sdf index ca3a256d..c502d77b 100644 --- a/sdformat_test_files/models/geometry_sphere/geometry_sphere.sdf +++ b/sdformat_test_files/models/geometry_sphere/geometry_sphere.sdf @@ -1,15 +1,15 @@ - - + + 0.125 - + 0.125 diff --git a/sdformat_test_files/models/graph_four_bar/graph_four_bar.sdf b/sdformat_test_files/models/graph_four_bar/graph_four_bar.sdf index 2be3cf2e..2c7b7c80 100644 --- a/sdformat_test_files/models/graph_four_bar/graph_four_bar.sdf +++ b/sdformat_test_files/models/graph_four_bar/graph_four_bar.sdf @@ -1,16 +1,16 @@ - + 0 0 0 0 0 0 - + 0.1 0.1 0.1 - + 0.1 0.1 0.1 @@ -29,16 +29,16 @@ - + 0 0.1 0.2 0 0 0 - + 0.1 0.1 0.1 - + 0.1 0.1 0.1 @@ -57,16 +57,16 @@ - + 0 0.4 0.2 0 0 0 - + 0.1 0.1 0.1 - + 0.1 0.1 0.1 @@ -85,16 +85,16 @@ - + 0 0.3 0 0 0 0 - + 0.1 0.1 0.1 - + 0.1 0.1 0.1 @@ -114,29 +114,29 @@ - graph_four_bar_link_1 - graph_four_bar_link_2 + link_1 + link_2 1 0 0 - graph_four_bar_link_2 - graph_four_bar_link_3 + link_2 + link_3 1 0 0 - graph_four_bar_link_3 - graph_four_bar_link_4 + link_3 + link_4 1 0 0 - graph_four_bar_link_4 - graph_four_bar_link_1 + link_4 + link_1 1 0 0 diff --git a/sdformat_test_files/models/graph_loop/graph_loop.sdf b/sdformat_test_files/models/graph_loop/graph_loop.sdf index a99db604..a2e62ee9 100644 --- a/sdformat_test_files/models/graph_loop/graph_loop.sdf +++ b/sdformat_test_files/models/graph_loop/graph_loop.sdf @@ -1,16 +1,16 @@ - + 0 0.1 0.2 0 0 0 - + 0.1 0.1 0.1 - + 0.1 0.1 0.1 @@ -29,16 +29,16 @@ - + 0 0 0 0 0 0 - + 0.1 0.1 0.1 - + 0.1 0.1 0.1 @@ -57,16 +57,16 @@ - + 0 0.2 0 0 0 0 - + 0.1 0.1 0.1 - + 0.1 0.1 0.1 @@ -86,22 +86,22 @@ - graph_loop_link_1 - graph_loop_link_2 + link_1 + link_2 1 0 0 - graph_loop_link_2 - graph_loop_link_3 + link_2 + link_3 1 0 0 - graph_loop_link_3 - graph_loop_link_1 + link_3 + link_1 1 0 0 diff --git a/sdformat_test_files/models/joint_fixed/joint_fixed.sdf b/sdformat_test_files/models/joint_fixed/joint_fixed.sdf index 43573c38..5b49e6c5 100644 --- a/sdformat_test_files/models/joint_fixed/joint_fixed.sdf +++ b/sdformat_test_files/models/joint_fixed/joint_fixed.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -28,16 +28,16 @@ - + 0.1 0 0.1 0 0 0 - + 0.1 0.2 0.3 - + 0.1 0.2 0.3 @@ -58,8 +58,8 @@ - joint_fixed_link_1 - joint_fixed_link_2 + link_1 + link_2 diff --git a/sdformat_test_files/models/joint_prismatic/joint_prismatic.sdf b/sdformat_test_files/models/joint_prismatic/joint_prismatic.sdf index a4670b0a..cd3b0d2f 100644 --- a/sdformat_test_files/models/joint_prismatic/joint_prismatic.sdf +++ b/sdformat_test_files/models/joint_prismatic/joint_prismatic.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -28,16 +28,16 @@ - + 0.1 0 0.1 0 0 0 - + 0.1 0.2 0.3 - + 0.1 0.2 0.3 @@ -58,8 +58,8 @@ - joint_prismatic_link_1 - joint_prismatic_link_2 + link_1 + link_2 0 1 0 diff --git a/sdformat_test_files/models/joint_revolute2/joint_revolute2.sdf b/sdformat_test_files/models/joint_revolute2/joint_revolute2.sdf index aaa33050..a70592a9 100644 --- a/sdformat_test_files/models/joint_revolute2/joint_revolute2.sdf +++ b/sdformat_test_files/models/joint_revolute2/joint_revolute2.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -28,16 +28,16 @@ - + 0.1 0 0.1 0 0 0 - + 0.1 0.2 0.3 - + 0.1 0.2 0.3 @@ -58,8 +58,8 @@ - joint_revolute2_link_1 - joint_revolute2_link_2 + link_1 + link_2 1 0 0 diff --git a/sdformat_test_files/models/joint_screw/joint_screw.sdf b/sdformat_test_files/models/joint_screw/joint_screw.sdf index 8f6c35e7..da1ea21a 100644 --- a/sdformat_test_files/models/joint_screw/joint_screw.sdf +++ b/sdformat_test_files/models/joint_screw/joint_screw.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -28,16 +28,16 @@ - + 0.1 0 0.1 0 0 0 - + 0.1 0.2 0.3 - + 0.1 0.2 0.3 @@ -58,8 +58,8 @@ - joint_screw_link_1 - joint_screw_link_2 + link_1 + link_2 0 0 1 diff --git a/sdformat_test_files/models/joint_universal/joint_universal.sdf b/sdformat_test_files/models/joint_universal/joint_universal.sdf index 9779d2d0..bf8cc337 100644 --- a/sdformat_test_files/models/joint_universal/joint_universal.sdf +++ b/sdformat_test_files/models/joint_universal/joint_universal.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -28,16 +28,16 @@ - + 0.1 0 0.1 0 0 0 - + 0.1 0.1 0.2 - + 0.1 0.1 0.2 @@ -58,8 +58,8 @@ - joint_universal_link_1 - joint_universal_link_2 + link_1 + link_2 0 0 0.1 0 0 0 diff --git a/sdformat_test_files/models/material_blinn_phong/material_blinn_phong.sdf b/sdformat_test_files/models/material_blinn_phong/material_blinn_phong.sdf index ac7aa6e5..e4cfa2b8 100644 --- a/sdformat_test_files/models/material_blinn_phong/material_blinn_phong.sdf +++ b/sdformat_test_files/models/material_blinn_phong/material_blinn_phong.sdf @@ -1,8 +1,8 @@ - - + + 0.2 0.2 0.2 @@ -15,7 +15,7 @@ 0.1 0.1 0.1 1 - + 0.2 0.2 0.2 diff --git a/sdformat_test_files/models/material_dynamic_lights/material_dynamic_lights.sdf b/sdformat_test_files/models/material_dynamic_lights/material_dynamic_lights.sdf index 0643fc8d..fe3439a6 100644 --- a/sdformat_test_files/models/material_dynamic_lights/material_dynamic_lights.sdf +++ b/sdformat_test_files/models/material_dynamic_lights/material_dynamic_lights.sdf @@ -1,8 +1,8 @@ - - + + 0.2 0.2 0.2 @@ -12,7 +12,7 @@ true - + 0.1 0.1 0.4 @@ -22,14 +22,14 @@ false - + 0.2 0.2 0.2 - + 0.1 0.1 0.4 diff --git a/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf b/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf index a9487c77..36229db7 100644 --- a/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf +++ b/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/material_pbr/material_pbr.sdf b/sdformat_test_files/models/material_pbr/material_pbr.sdf index 69242ba5..44214a5a 100644 --- a/sdformat_test_files/models/material_pbr/material_pbr.sdf +++ b/sdformat_test_files/models/material_pbr/material_pbr.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/material_shader/material_shader.sdf b/sdformat_test_files/models/material_shader/material_shader.sdf index 0abd442e..857625a4 100644 --- a/sdformat_test_files/models/material_shader/material_shader.sdf +++ b/sdformat_test_files/models/material_shader/material_shader.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/model.sdf b/sdformat_test_files/models/model.sdf new file mode 100644 index 00000000..350f4a17 --- /dev/null +++ b/sdformat_test_files/models/model.sdf @@ -0,0 +1,32 @@ + + + + + + + + 0.1 0.2 0.4 + + + + + + + 0.1 0.2 0.4 + + + + + 1.23 + + 0.0205 + 0 + 0 + 0.017425 + 0 + 0.005125 + + + + + diff --git a/sdformat_test_files/models/pose_chain/pose_chain.sdf b/sdformat_test_files/models/pose_chain/pose_chain.sdf index 800b6405..3d2c5479 100644 --- a/sdformat_test_files/models/pose_chain/pose_chain.sdf +++ b/sdformat_test_files/models/pose_chain/pose_chain.sdf @@ -1,16 +1,16 @@ - + 0.1 0.2 0.3 0.4 0.5 0.6 - + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -29,16 +29,16 @@ - + 0.2 0.3 0.4 0.5 0.6 0.7 - + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -57,16 +57,16 @@ - + 0.3 0.4 0.5 0.6 0.7 0.8 - + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -85,16 +85,16 @@ - + 0.4 0.5 0.6 0.7 0.8 0.9 - + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -115,8 +115,8 @@ 0.9 0.8 0.7 0.6 0.5 0.4 - pose_chain_link_1 - pose_chain_link_2 + link_1 + link_2 1 0 0 @@ -127,8 +127,8 @@ 0.8 0.7 0.6 0.5 0.4 0.3 - pose_chain_link_2 - pose_chain_link_3 + link_2 + link_3 1 0 0 @@ -139,8 +139,8 @@ 0.7 0.6 0.5 0.4 0.3 0.2 - pose_chain_link_3 - pose_chain_link_4 + link_3 + link_4 1 0 0 diff --git a/sdformat_test_files/models/pose_collision/pose_collision.sdf b/sdformat_test_files/models/pose_collision/pose_collision.sdf index 34533269..7a2cf4c5 100644 --- a/sdformat_test_files/models/pose_collision/pose_collision.sdf +++ b/sdformat_test_files/models/pose_collision/pose_collision.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.05 0.1 0.2 0.1 0.2 0.3 diff --git a/sdformat_test_files/models/pose_collision_in_frame/pose_collision_in_frame.sdf b/sdformat_test_files/models/pose_collision_in_frame/pose_collision_in_frame.sdf index 4dc1ad57..43be1553 100644 --- a/sdformat_test_files/models/pose_collision_in_frame/pose_collision_in_frame.sdf +++ b/sdformat_test_files/models/pose_collision_in_frame/pose_collision_in_frame.sdf @@ -4,15 +4,15 @@ 0.05 0.1 0.2 0.1 0.2 0.3 - - + + 0.1 0.2 0.4 - + 0.2 0.4 0.8 0.2 0.3 0.4 diff --git a/sdformat_test_files/models/pose_inertial/pose_inertial.sdf b/sdformat_test_files/models/pose_inertial/pose_inertial.sdf index 6ea8f73f..2aaa6773 100644 --- a/sdformat_test_files/models/pose_inertial/pose_inertial.sdf +++ b/sdformat_test_files/models/pose_inertial/pose_inertial.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/pose_inertial_in_frame/pose_inertial_in_frame.sdf b/sdformat_test_files/models/pose_inertial_in_frame/pose_inertial_in_frame.sdf index 5e1b309d..aed6ccc6 100644 --- a/sdformat_test_files/models/pose_inertial_in_frame/pose_inertial_in_frame.sdf +++ b/sdformat_test_files/models/pose_inertial_in_frame/pose_inertial_in_frame.sdf @@ -4,15 +4,15 @@ 0.05 0.1 0.2 0.1 0.2 0.3 - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/pose_joint/pose_joint.sdf b/sdformat_test_files/models/pose_joint/pose_joint.sdf index 1e62e036..c1f47374 100644 --- a/sdformat_test_files/models/pose_joint/pose_joint.sdf +++ b/sdformat_test_files/models/pose_joint/pose_joint.sdf @@ -1,15 +1,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -28,15 +28,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -57,8 +57,8 @@ 0.05 0.1 0.2 0.1 0.2 0.3 - pose_joint_link_1 - pose_joint_link_2 + link_1 + link_2 1 0 0 diff --git a/sdformat_test_files/models/pose_joint_in_frame/pose_joint_in_frame.sdf b/sdformat_test_files/models/pose_joint_in_frame/pose_joint_in_frame.sdf index 64950bca..f46ed8af 100644 --- a/sdformat_test_files/models/pose_joint_in_frame/pose_joint_in_frame.sdf +++ b/sdformat_test_files/models/pose_joint_in_frame/pose_joint_in_frame.sdf @@ -4,15 +4,15 @@ 0.05 0.1 0.2 0.1 0.2 0.3 - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -31,15 +31,15 @@ - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 @@ -60,8 +60,8 @@ 0.05 0.1 0.2 0.1 0.2 0.3 - pose_joint_in_frame_link_1 - pose_joint_in_frame_link_2 + link_1 + link_2 1 0 0 diff --git a/sdformat_test_files/models/pose_link/pose_link.sdf b/sdformat_test_files/models/pose_link/pose_link.sdf index a110b565..49fff708 100644 --- a/sdformat_test_files/models/pose_link/pose_link.sdf +++ b/sdformat_test_files/models/pose_link/pose_link.sdf @@ -1,16 +1,16 @@ - + 0.05 0.1 0.2 0.1 0.2 0.3 - + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/pose_link_all/pose_link_all.sdf b/sdformat_test_files/models/pose_link_all/pose_link_all.sdf index 65e90062..8584c549 100644 --- a/sdformat_test_files/models/pose_link_all/pose_link_all.sdf +++ b/sdformat_test_files/models/pose_link_all/pose_link_all.sdf @@ -1,9 +1,9 @@ - + 0.05 0.1 0.2 0.1 0.2 0.3 - + 0.03 0.6 0.12 0.2 0.3 0.4 @@ -11,7 +11,7 @@ - + 0.04 0.8 0.16 0.3 0.4 0.5 diff --git a/sdformat_test_files/models/pose_link_in_frame/pose_link_in_frame.sdf b/sdformat_test_files/models/pose_link_in_frame/pose_link_in_frame.sdf index 29b8b6fb..0a3ae6fd 100644 --- a/sdformat_test_files/models/pose_link_in_frame/pose_link_in_frame.sdf +++ b/sdformat_test_files/models/pose_link_in_frame/pose_link_in_frame.sdf @@ -4,16 +4,16 @@ 0.05 0.1 0.2 0.1 0.2 0.3 - + 0.2 0.4 0.8 0.2 0.3 0.4 - + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/pose_model/pose_model.sdf b/sdformat_test_files/models/pose_model/pose_model.sdf index e65b2f79..7d7d4c21 100644 --- a/sdformat_test_files/models/pose_model/pose_model.sdf +++ b/sdformat_test_files/models/pose_model/pose_model.sdf @@ -2,15 +2,15 @@ 0.05 0.1 0.2 0.1 0.2 0.3 - - + + 0.1 0.2 0.4 - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/pose_visual/pose_visual.sdf b/sdformat_test_files/models/pose_visual/pose_visual.sdf index 09eaf128..ee1c4a6b 100644 --- a/sdformat_test_files/models/pose_visual/pose_visual.sdf +++ b/sdformat_test_files/models/pose_visual/pose_visual.sdf @@ -1,8 +1,8 @@ - - + + 0.05 0.1 0.2 0.1 0.2 0.3 @@ -10,7 +10,7 @@ - + 0.1 0.2 0.4 diff --git a/sdformat_test_files/models/pose_visual_in_frame/pose_visual_in_frame.sdf b/sdformat_test_files/models/pose_visual_in_frame/pose_visual_in_frame.sdf index 86eab968..0629790c 100644 --- a/sdformat_test_files/models/pose_visual_in_frame/pose_visual_in_frame.sdf +++ b/sdformat_test_files/models/pose_visual_in_frame/pose_visual_in_frame.sdf @@ -4,8 +4,8 @@ 0.05 0.1 0.2 0.1 0.2 0.3 - - + + 0.2 0.4 0.8 0.2 0.3 0.4 @@ -13,7 +13,7 @@ - + 0.1 0.2 0.4 diff --git a/sdformat_urdf/test/pose_tests.cpp b/sdformat_urdf/test/pose_tests.cpp index 1d8eed0f..c7c4ab78 100644 --- a/sdformat_urdf/test/pose_tests.cpp +++ b/sdformat_urdf/test/pose_tests.cpp @@ -35,13 +35,13 @@ TEST(Pose, pose_chain) ASSERT_EQ(4u, model->links_.size()); ASSERT_EQ(3u, model->joints_.size()); - urdf::LinkConstSharedPtr link_1 = model->getLink("pose_chain_link_1"); + urdf::LinkConstSharedPtr link_1 = model->getLink("link_1"); ASSERT_NE(nullptr, link_1); - urdf::LinkConstSharedPtr link_2 = model->getLink("pose_chain_link_2"); + urdf::LinkConstSharedPtr link_2 = model->getLink("link_2"); ASSERT_NE(nullptr, link_2); - urdf::LinkConstSharedPtr link_3 = model->getLink("pose_chain_link_3"); + urdf::LinkConstSharedPtr link_3 = model->getLink("link_3"); ASSERT_NE(nullptr, link_3); - urdf::LinkConstSharedPtr link_4 = model->getLink("pose_chain_link_4"); + urdf::LinkConstSharedPtr link_4 = model->getLink("link_4"); ASSERT_NE(nullptr, link_4); urdf::JointConstSharedPtr joint_1 = model->getJoint("joint_1"); From fc8490a337f58e4ba05a765ba62860aeeac5eb62 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 9 Oct 2020 08:34:02 -0700 Subject: [PATCH 112/152] Remove accidentally comitted file Signed-off-by: Shane Loretz --- sdformat_test_files/models/model.sdf | 32 ---------------------------- 1 file changed, 32 deletions(-) delete mode 100644 sdformat_test_files/models/model.sdf diff --git a/sdformat_test_files/models/model.sdf b/sdformat_test_files/models/model.sdf deleted file mode 100644 index 350f4a17..00000000 --- a/sdformat_test_files/models/model.sdf +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - 0.1 0.2 0.4 - - - - - - - 0.1 0.2 0.4 - - - - - 1.23 - - 0.0205 - 0 - 0 - 0.017425 - 0 - 0.005125 - - - - - From c816318bbf0f7c52aae90347e6aa3d7593425405 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 9 Oct 2020 08:51:01 -0700 Subject: [PATCH 113/152] Add material_blinn_phong test Signed-off-by: Shane Loretz --- sdformat_urdf/CMakeLists.txt | 7 +++++ sdformat_urdf/test/material_tests.cpp | 43 +++++++++++++++++++++++++++ sdformat_urdf/test/sdf_paths.hpp.in | 1 + 3 files changed, 51 insertions(+) create mode 100644 sdformat_urdf/test/material_tests.cpp diff --git a/sdformat_urdf/CMakeLists.txt b/sdformat_urdf/CMakeLists.txt index 9817649b..bd7118e8 100644 --- a/sdformat_urdf/CMakeLists.txt +++ b/sdformat_urdf/CMakeLists.txt @@ -108,6 +108,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_collisions" "link_multiple_collisions") sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_visuals" "link_multiple_visuals") sdformat_test_files_get_model_sdf("path_to_sdf_link_sensor_imu" "link_sensor_imu") + sdformat_test_files_get_model_sdf("path_to_sdf_material_blinn_phong" "material_blinn_phong") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") @@ -149,6 +150,12 @@ if(BUILD_TESTING) "${CMAKE_CURRENT_SOURCE_DIR}/test/include" "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_material_tests "test/material_tests.cpp") + target_link_libraries(sdf_material_tests sdformat_urdf) + target_include_directories(sdf_material_tests PRIVATE + "${CMAKE_CURRENT_SOURCE_DIR}/test/include" + "${CMAKE_CURRENT_BINARY_DIR}/generated_includes") + ament_add_gtest(sdf_model_tests "test/model_tests.cpp") target_link_libraries(sdf_model_tests sdformat_urdf) target_include_directories(sdf_model_tests PRIVATE diff --git a/sdformat_urdf/test/material_tests.cpp b/sdformat_urdf/test/material_tests.cpp new file mode 100644 index 00000000..c5e85e00 --- /dev/null +++ b/sdformat_urdf/test/material_tests.cpp @@ -0,0 +1,43 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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 +#include +#include +#include +#include + +#include "sdf_paths.hpp" +#include "test_tools.hpp" + +TEST(Material, material_blinn_phong) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_MATERIAL_BLINN_PHONG), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("material_blinn_phong", model->getName()); + + urdf::VisualConstSharedPtr visual = model->getRoot()->visual; + ASSERT_NE(nullptr, visual); + + EXPECT_EQ(visual->name, visual->material->name); + EXPECT_EQ("", visual->material->texture_filename); + EXPECT_FLOAT_EQ(0.3, visual->material->color.r); + EXPECT_FLOAT_EQ(0, visual->material->color.g); + EXPECT_FLOAT_EQ(0, visual->material->color.b); + EXPECT_FLOAT_EQ(1, visual->material->color.a); +} diff --git a/sdformat_urdf/test/sdf_paths.hpp.in b/sdformat_urdf/test/sdf_paths.hpp.in index ef66a1ae..89d28a23 100644 --- a/sdformat_urdf/test/sdf_paths.hpp.in +++ b/sdformat_urdf/test/sdf_paths.hpp.in @@ -47,6 +47,7 @@ #define PATH_TO_SDF_LINK_MULTIPLE_COLLISIONS "@path_to_sdf_link_multiple_collisions@" #define PATH_TO_SDF_LINK_MULTIPLE_VISUALS "@path_to_sdf_link_multiple_visuals@" #define PATH_TO_SDF_LINK_SENSOR_IMU "@path_to_sdf_link_sensor_imu@" +#define PATH_TO_SDF_MATERIAL_BLINN_PHONG "@path_to_sdf_material_blinn_phong@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 41c3f8e6d43f53576aaa62f06e52278f06d91676 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 9 Oct 2020 09:57:54 -0700 Subject: [PATCH 114/152] Warn if unsupported feature is used Signed-off-by: Shane Loretz --- sdformat_urdf/src/sdformat_urdf.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/sdformat_urdf/src/sdformat_urdf.cpp b/sdformat_urdf/src/sdformat_urdf.cpp index b0c30597..64d98296 100644 --- a/sdformat_urdf/src/sdformat_urdf.cpp +++ b/sdformat_urdf/src/sdformat_urdf.cpp @@ -394,6 +394,14 @@ sdformat_urdf::convert_link( urdf_material->color.a = sdf_material->Ambient().A(); urdf_visual->material = urdf_material; + + // Warn about unsupported features + if (!sdf_material->Lighting()) { + RCUTILS_LOG_WARN_NAMED( + "sdformat_urdf", "SDFormat visual [%s] has ," + " but URDF does not support this", sdf_visual->Name().c_str()); + } + std::cerr << "has material\n"; } if (0u == vi) { From bf74e9daa33ddb5967d58fb16d97b06f58d7828f Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 9 Oct 2020 09:58:25 -0700 Subject: [PATCH 115/152] Add skipped material_dynamic_lights test Signed-off-by: Shane Loretz --- sdformat_urdf/CMakeLists.txt | 1 + sdformat_urdf/test/material_tests.cpp | 14 ++++++++++++++ sdformat_urdf/test/sdf_paths.hpp.in | 1 + 3 files changed, 16 insertions(+) diff --git a/sdformat_urdf/CMakeLists.txt b/sdformat_urdf/CMakeLists.txt index bd7118e8..5744a53d 100644 --- a/sdformat_urdf/CMakeLists.txt +++ b/sdformat_urdf/CMakeLists.txt @@ -109,6 +109,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_link_multiple_visuals" "link_multiple_visuals") sdformat_test_files_get_model_sdf("path_to_sdf_link_sensor_imu" "link_sensor_imu") sdformat_test_files_get_model_sdf("path_to_sdf_material_blinn_phong" "material_blinn_phong") + sdformat_test_files_get_model_sdf("path_to_sdf_material_dynamic_lights" "material_dynamic_lights") sdformat_test_files_get_model_sdf("path_to_sdf_model_two_models" "model_two_models") sdformat_test_files_get_model_sdf("path_to_sdf_model_zero_models" "model_zero_models") sdformat_test_files_get_model_sdf("path_to_sdf_pose_chain" "pose_chain") diff --git a/sdformat_urdf/test/material_tests.cpp b/sdformat_urdf/test/material_tests.cpp index c5e85e00..4b0988e1 100644 --- a/sdformat_urdf/test/material_tests.cpp +++ b/sdformat_urdf/test/material_tests.cpp @@ -41,3 +41,17 @@ TEST(Material, material_blinn_phong) EXPECT_FLOAT_EQ(0, visual->material->color.b); EXPECT_FLOAT_EQ(1, visual->material->color.a); } + +TEST(Material, material_dynamic_lights) +{ + GTEST_SKIP() << "https://github.com/osrf/sdformat/issues/384"; + + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_MATERIAL_DYNAMIC_LIGHTS), errors); + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_TRUE(model); + ASSERT_EQ("material_dynamic_lights", model->getName()); + + // URDF doesn't support toggling dynamic lights, so a warning is omitted to the console +} diff --git a/sdformat_urdf/test/sdf_paths.hpp.in b/sdformat_urdf/test/sdf_paths.hpp.in index 89d28a23..02d459db 100644 --- a/sdformat_urdf/test/sdf_paths.hpp.in +++ b/sdformat_urdf/test/sdf_paths.hpp.in @@ -48,6 +48,7 @@ #define PATH_TO_SDF_LINK_MULTIPLE_VISUALS "@path_to_sdf_link_multiple_visuals@" #define PATH_TO_SDF_LINK_SENSOR_IMU "@path_to_sdf_link_sensor_imu@" #define PATH_TO_SDF_MATERIAL_BLINN_PHONG "@path_to_sdf_material_blinn_phong@" +#define PATH_TO_SDF_MATERIAL_DYNAMIC_LIGHTS "@path_to_sdf_material_dynamic_lights@" #define PATH_TO_SDF_MODEL_TWO_MODELS "@path_to_sdf_model_two_models@" #define PATH_TO_SDF_MODEL_ZERO_MODELS "@path_to_sdf_model_zero_models@" #define PATH_TO_SDF_POSE_CHAIN "@path_to_sdf_pose_chain@" From 2f46b1c9d4ece71ede46bcbdd74b7b5e9ab745c7 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 9 Oct 2020 11:25:59 -0700 Subject: [PATCH 116/152] Remove unfinished material models and add TODO for them Signed-off-by: Shane Loretz --- sdformat_test_files/CMakeLists.txt | 3 -- .../material_ogre_script.sdf | 32 ------------------- .../models/material_ogre_script/model.config | 14 -------- .../models/material_pbr/material_pbr.sdf | 32 ------------------- .../models/material_pbr/model.config | 14 -------- .../material_shader/material_shader.sdf | 32 ------------------- .../models/material_shader/model.config | 14 -------- sdformat_urdf/src/sdformat_urdf.cpp | 2 +- 8 files changed, 1 insertion(+), 142 deletions(-) delete mode 100644 sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf delete mode 100644 sdformat_test_files/models/material_ogre_script/model.config delete mode 100644 sdformat_test_files/models/material_pbr/material_pbr.sdf delete mode 100644 sdformat_test_files/models/material_pbr/model.config delete mode 100644 sdformat_test_files/models/material_shader/material_shader.sdf delete mode 100644 sdformat_test_files/models/material_shader/model.config diff --git a/sdformat_test_files/CMakeLists.txt b/sdformat_test_files/CMakeLists.txt index fc023dd3..99c2282d 100644 --- a/sdformat_test_files/CMakeLists.txt +++ b/sdformat_test_files/CMakeLists.txt @@ -49,9 +49,6 @@ set(model_names "link_sensor_imu" "material_blinn_phong" "material_dynamic_lights" - "material_ogre_script" - "material_pbr" - "material_shader" "model_two_models" "model_zero_models" "pose_chain" diff --git a/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf b/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf deleted file mode 100644 index 36229db7..00000000 --- a/sdformat_test_files/models/material_ogre_script/material_ogre_script.sdf +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - 0.1 0.2 0.4 - - - - - - - 0.1 0.2 0.4 - - - - - 1.23 - - 0.0205 - 0 - 0 - 0.017425 - 0 - 0.005125 - - - - - diff --git a/sdformat_test_files/models/material_ogre_script/model.config b/sdformat_test_files/models/material_ogre_script/model.config deleted file mode 100644 index 09634739..00000000 --- a/sdformat_test_files/models/material_ogre_script/model.config +++ /dev/null @@ -1,14 +0,0 @@ - - - material_ogre_script - 1.0 - material_ogre_script.sdf - - - Shane Loretz - sloretz@openrobotics.org - - - - - diff --git a/sdformat_test_files/models/material_pbr/material_pbr.sdf b/sdformat_test_files/models/material_pbr/material_pbr.sdf deleted file mode 100644 index 44214a5a..00000000 --- a/sdformat_test_files/models/material_pbr/material_pbr.sdf +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - 0.1 0.2 0.4 - - - - - - - 0.1 0.2 0.4 - - - - - 1.23 - - 0.0205 - 0 - 0 - 0.017425 - 0 - 0.005125 - - - - - diff --git a/sdformat_test_files/models/material_pbr/model.config b/sdformat_test_files/models/material_pbr/model.config deleted file mode 100644 index ca5b1aa3..00000000 --- a/sdformat_test_files/models/material_pbr/model.config +++ /dev/null @@ -1,14 +0,0 @@ - - - material_pbr - 1.0 - material_pbr.sdf - - - Shane Loretz - sloretz@openrobotics.org - - - - - diff --git a/sdformat_test_files/models/material_shader/material_shader.sdf b/sdformat_test_files/models/material_shader/material_shader.sdf deleted file mode 100644 index 857625a4..00000000 --- a/sdformat_test_files/models/material_shader/material_shader.sdf +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - 0.1 0.2 0.4 - - - - - - - 0.1 0.2 0.4 - - - - - 1.23 - - 0.0205 - 0 - 0 - 0.017425 - 0 - 0.005125 - - - - - diff --git a/sdformat_test_files/models/material_shader/model.config b/sdformat_test_files/models/material_shader/model.config deleted file mode 100644 index 4148e8d7..00000000 --- a/sdformat_test_files/models/material_shader/model.config +++ /dev/null @@ -1,14 +0,0 @@ - - - material_shader - 1.0 - material_shader.sdf - - - Shane Loretz - sloretz@openrobotics.org - - - - - diff --git a/sdformat_urdf/src/sdformat_urdf.cpp b/sdformat_urdf/src/sdformat_urdf.cpp index 64d98296..603670db 100644 --- a/sdformat_urdf/src/sdformat_urdf.cpp +++ b/sdformat_urdf/src/sdformat_urdf.cpp @@ -401,7 +401,7 @@ sdformat_urdf::convert_link( "sdformat_urdf", "SDFormat visual [%s] has ," " but URDF does not support this", sdf_visual->Name().c_str()); } - std::cerr << "has material\n"; + // TODO(sloretz) warn about materials with ogre scripts, shaders, and pbr } if (0u == vi) { From 8bbee668c7452d414f1f8f1d580d20e232151b57 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 9 Oct 2020 12:05:19 -0700 Subject: [PATCH 117/152] Expect no Algorithm errors Signed-off-by: Shane Loretz --- sdformat_urdf/test/geometry_tests.cpp | 2 ++ sdformat_urdf/test/graph_tests.cpp | 4 ++++ sdformat_urdf/test/include/test_tools.hpp | 10 ++++++++++ sdformat_urdf/test/joint_tests.cpp | 5 +++++ sdformat_urdf/test/model_tests.cpp | 2 ++ sdformat_urdf/test/pose_tests.cpp | 1 + 6 files changed, 24 insertions(+) diff --git a/sdformat_urdf/test/geometry_tests.cpp b/sdformat_urdf/test/geometry_tests.cpp index 0c641243..7171730f 100644 --- a/sdformat_urdf/test/geometry_tests.cpp +++ b/sdformat_urdf/test/geometry_tests.cpp @@ -90,6 +90,7 @@ TEST(Geometry, geometry_heightmap) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_GEOMETRY_HEIGHTMAP), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -221,6 +222,7 @@ TEST(Geometry, geometry_plane) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_GEOMETRY_PLANE), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } diff --git a/sdformat_urdf/test/graph_tests.cpp b/sdformat_urdf/test/graph_tests.cpp index c315ea69..23d8b319 100644 --- a/sdformat_urdf/test/graph_tests.cpp +++ b/sdformat_urdf/test/graph_tests.cpp @@ -85,6 +85,7 @@ TEST(Graph, graph_chain_non_canonical_root) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_GRAPH_CHAIN_NON_CANONICAL_ROOT), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -94,6 +95,7 @@ TEST(Graph, graph_four_bar) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_GRAPH_FOUR_BAR), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -103,6 +105,7 @@ TEST(Graph, graph_loop) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_GRAPH_LOOP), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -217,5 +220,6 @@ TEST(Graph, graph_tree_non_canonical_root) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_GRAPH_TREE_NON_CANONICAL_ROOT), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } diff --git a/sdformat_urdf/test/include/test_tools.hpp b/sdformat_urdf/test/include/test_tools.hpp index b4dcec71..bc5edaef 100644 --- a/sdformat_urdf/test/include/test_tools.hpp +++ b/sdformat_urdf/test/include/test_tools.hpp @@ -17,6 +17,7 @@ #include +#include #include #include #include @@ -65,6 +66,15 @@ get_file(const char * path) } \ } while (false) +#define EXPECT_NO_ALGORITHM_ERRORS(errors) \ + do { \ + for (const auto & error : errors) { \ + const std::string msg = error.Message(); \ + if (std::string::npos != msg.find("Algorithm error")) { \ + EXPECT_TRUE(false) << msg; \ + } \ + } \ + } while (false) std::ostream & operator<<(std::ostream & os, const sdf::Errors & errors) { diff --git a/sdformat_urdf/test/joint_tests.cpp b/sdformat_urdf/test/joint_tests.cpp index 100142ea..4f841f95 100644 --- a/sdformat_urdf/test/joint_tests.cpp +++ b/sdformat_urdf/test/joint_tests.cpp @@ -28,6 +28,7 @@ TEST(Joint, joint_ball) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_JOINT_BALL), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -137,6 +138,7 @@ TEST(Joint, joint_revolute2) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_JOINT_REVOLUTE2), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -214,6 +216,7 @@ TEST(Joint, joint_revolute_two_joints_two_links) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_JOINT_REVOLUTE_TWO_JOINTS_TWO_LINKS), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -223,6 +226,7 @@ TEST(Joint, joint_screw) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_JOINT_SCREW), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -232,5 +236,6 @@ TEST(Joint, joint_universal) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_JOINT_UNIVERSAL), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } diff --git a/sdformat_urdf/test/model_tests.cpp b/sdformat_urdf/test/model_tests.cpp index 6ccec8ac..7292fd31 100644 --- a/sdformat_urdf/test/model_tests.cpp +++ b/sdformat_urdf/test/model_tests.cpp @@ -28,6 +28,7 @@ TEST(Model, model_two_models) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_MODEL_TWO_MODELS), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } @@ -37,5 +38,6 @@ TEST(Model, model_zero_models) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_MODEL_ZERO_MODELS), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } diff --git a/sdformat_urdf/test/pose_tests.cpp b/sdformat_urdf/test/pose_tests.cpp index c7c4ab78..a392f971 100644 --- a/sdformat_urdf/test/pose_tests.cpp +++ b/sdformat_urdf/test/pose_tests.cpp @@ -333,6 +333,7 @@ TEST(Pose, pose_model) urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( get_file(PATH_TO_SDF_POSE_MODEL), errors); EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); ASSERT_FALSE(model); } From f967e20763a8e792e53e52cb5ee77ab170f099de Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 9 Oct 2020 15:55:26 -0700 Subject: [PATCH 118/152] Add joint_gearbox model and test Signed-off-by: Shane Loretz --- .../models/joint_gearbox/joint_gearbox.sdf | 101 ++++++++++++++++-- sdformat_urdf/CMakeLists.txt | 1 + sdformat_urdf/test/joint_tests.cpp | 10 ++ sdformat_urdf/test/sdf_paths.hpp.in | 1 + 4 files changed, 105 insertions(+), 8 deletions(-) diff --git a/sdformat_test_files/models/joint_gearbox/joint_gearbox.sdf b/sdformat_test_files/models/joint_gearbox/joint_gearbox.sdf index b6239421..67ffb9a6 100644 --- a/sdformat_test_files/models/joint_gearbox/joint_gearbox.sdf +++ b/sdformat_test_files/models/joint_gearbox/joint_gearbox.sdf @@ -1,32 +1,117 @@ - - + + 0 0 0.2 0 0 0 + - 0.1 0.2 0.4 + 0.2 0.2 0.4 - + - 0.1 0.2 0.4 + 0.2 0.2 0.4 + + + + + 12.3 + + 0.205 + 0 + 0 + 0.205 + 0 + 0.082 + + + + + 0 -0.2 0.4 0 0 0 + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + 1.23 + + 0.00205 + 0 + 0 + 0.00205 + 0 + 0.00205 + + + + + 0 0.3 0.4 0 0 0 + + + + 0.3 0.3 0.3 + + + + + + + 0.3 0.3 0.3 1.23 - 0.0205 + 0.01845 0 0 - 0.017425 + 0.01845 0 - 0.005125 + 0.01845 + + + link_1 + link_2 + + 0 1 0 + + + + link_1 + link_3 + + 0 1 0 + + + + + link_3 + link_2 + -27 + link_1 + + 0 1 0 + + + 0 1 0 + + diff --git a/sdformat_urdf/CMakeLists.txt b/sdformat_urdf/CMakeLists.txt index 5744a53d..d36a4a23 100644 --- a/sdformat_urdf/CMakeLists.txt +++ b/sdformat_urdf/CMakeLists.txt @@ -94,6 +94,7 @@ if(BUILD_TESTING) sdformat_test_files_get_model_sdf("path_to_sdf_joint_ball" "joint_ball") sdformat_test_files_get_model_sdf("path_to_sdf_joint_continuous" "joint_continuous") sdformat_test_files_get_model_sdf("path_to_sdf_joint_fixed" "joint_fixed") + sdformat_test_files_get_model_sdf("path_to_sdf_joint_gearbox" "joint_gearbox") sdformat_test_files_get_model_sdf("path_to_sdf_joint_prismatic" "joint_prismatic") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute" "joint_revolute") sdformat_test_files_get_model_sdf("path_to_sdf_joint_revolute2" "joint_revolute2") diff --git a/sdformat_urdf/test/joint_tests.cpp b/sdformat_urdf/test/joint_tests.cpp index 4f841f95..3c486eba 100644 --- a/sdformat_urdf/test/joint_tests.cpp +++ b/sdformat_urdf/test/joint_tests.cpp @@ -77,6 +77,16 @@ TEST(Joint, joint_fixed) ASSERT_EQ(nullptr, joint->mimic); } +TEST(Joint, joint_gearbox) +{ + sdf::Errors errors; + urdf::ModelInterfaceSharedPtr model = sdformat_urdf::parse( + get_file(PATH_TO_SDF_JOINT_GEARBOX), errors); + EXPECT_FALSE(errors.empty()); + EXPECT_NO_ALGORITHM_ERRORS(errors); + ASSERT_FALSE(model); +} + TEST(Joint, joint_prismatic) { sdf::Errors errors; diff --git a/sdformat_urdf/test/sdf_paths.hpp.in b/sdformat_urdf/test/sdf_paths.hpp.in index 02d459db..43a2e5fa 100644 --- a/sdformat_urdf/test/sdf_paths.hpp.in +++ b/sdformat_urdf/test/sdf_paths.hpp.in @@ -33,6 +33,7 @@ #define PATH_TO_SDF_JOINT_BALL "@path_to_sdf_joint_ball@" #define PATH_TO_SDF_JOINT_CONTINUOUS "@path_to_sdf_joint_continuous@" #define PATH_TO_SDF_JOINT_FIXED "@path_to_sdf_joint_fixed@" +#define PATH_TO_SDF_JOINT_GEARBOX "@path_to_sdf_joint_gearbox@" #define PATH_TO_SDF_JOINT_PRISMATIC "@path_to_sdf_joint_prismatic@" #define PATH_TO_SDF_JOINT_REVOLUTE "@path_to_sdf_joint_revolute@" #define PATH_TO_SDF_JOINT_REVOLUTE2 "@path_to_sdf_joint_revolute2@" From d57948b6f3e262a4f6f4db6287e2df6368252298 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 13 Oct 2020 15:14:04 -0700 Subject: [PATCH 119/152] Update descriptions of all models Signed-off-by: Shane Loretz --- sdformat_test_files/models/geometry_box/model.config | 2 +- sdformat_test_files/models/geometry_cylinder/model.config | 2 +- sdformat_test_files/models/geometry_heightmap/model.config | 1 + sdformat_test_files/models/geometry_mesh_scaled/model.config | 1 + sdformat_test_files/models/geometry_mesh_stl/model.config | 2 +- sdformat_test_files/models/geometry_plane/model.config | 2 +- sdformat_test_files/models/geometry_sphere/model.config | 2 +- sdformat_test_files/models/graph_chain/model.config | 1 + .../models/graph_chain_non_canonical_root/model.config | 1 + sdformat_test_files/models/graph_four_bar/model.config | 1 + sdformat_test_files/models/graph_loop/model.config | 1 + sdformat_test_files/models/graph_tree/model.config | 1 + .../models/graph_tree_non_canonical_root/model.config | 1 + sdformat_test_files/models/joint_ball/model.config | 2 +- sdformat_test_files/models/joint_continuous/model.config | 2 +- sdformat_test_files/models/joint_fixed/model.config | 2 +- sdformat_test_files/models/joint_gearbox/model.config | 2 +- sdformat_test_files/models/joint_prismatic/model.config | 2 +- sdformat_test_files/models/joint_revolute/model.config | 2 +- sdformat_test_files/models/joint_revolute2/model.config | 2 +- sdformat_test_files/models/joint_revolute_axis/model.config | 1 + .../models/joint_revolute_axis_in_frame/model.config | 1 + .../models/joint_revolute_default_limits/model.config | 1 + .../models/joint_revolute_two_joints_two_links/model.config | 1 + sdformat_test_files/models/joint_screw/model.config | 2 +- sdformat_test_files/models/joint_universal/model.config | 2 +- sdformat_test_files/models/link_inertia/model.config | 1 + sdformat_test_files/models/link_light_point/model.config | 1 + .../models/link_multiple_collisions/model.config | 1 + sdformat_test_files/models/link_multiple_visuals/model.config | 1 + sdformat_test_files/models/link_sensor_imu/model.config | 1 + sdformat_test_files/models/material_blinn_phong/model.config | 2 +- sdformat_test_files/models/material_dynamic_lights/model.config | 2 +- sdformat_test_files/models/model_two_models/model.config | 1 + sdformat_test_files/models/model_zero_models/model.config | 1 + sdformat_test_files/models/pose_chain/model.config | 1 + sdformat_test_files/models/pose_collision/model.config | 1 + sdformat_test_files/models/pose_collision_in_frame/model.config | 1 + sdformat_test_files/models/pose_inertial/model.config | 1 + sdformat_test_files/models/pose_inertial_in_frame/model.config | 1 + sdformat_test_files/models/pose_joint/model.config | 1 + sdformat_test_files/models/pose_joint_in_frame/model.config | 1 + sdformat_test_files/models/pose_link/model.config | 1 + sdformat_test_files/models/pose_link_all/model.config | 1 + sdformat_test_files/models/pose_link_in_frame/model.config | 1 + sdformat_test_files/models/pose_model/model.config | 1 + sdformat_test_files/models/pose_visual/model.config | 1 + sdformat_test_files/models/pose_visual_in_frame/model.config | 1 + 48 files changed, 48 insertions(+), 16 deletions(-) diff --git a/sdformat_test_files/models/geometry_box/model.config b/sdformat_test_files/models/geometry_box/model.config index 1d8c2c7d..cce70316 100644 --- a/sdformat_test_files/models/geometry_box/model.config +++ b/sdformat_test_files/models/geometry_box/model.config @@ -10,6 +10,6 @@ - A box using only the box geometry type for both the visual and collision and a color. + A single-link model using the box geometry type for both the visual and collision. diff --git a/sdformat_test_files/models/geometry_cylinder/model.config b/sdformat_test_files/models/geometry_cylinder/model.config index 9bc60ccf..146ce8aa 100644 --- a/sdformat_test_files/models/geometry_cylinder/model.config +++ b/sdformat_test_files/models/geometry_cylinder/model.config @@ -10,6 +10,6 @@ - A cylinder using only the cylinder geometry type for both the visual and collision and a color. + A single-link model using the cylinder geometry type for both the visual and collision. diff --git a/sdformat_test_files/models/geometry_heightmap/model.config b/sdformat_test_files/models/geometry_heightmap/model.config index fbf1bcbb..339712e2 100644 --- a/sdformat_test_files/models/geometry_heightmap/model.config +++ b/sdformat_test_files/models/geometry_heightmap/model.config @@ -10,5 +10,6 @@ + A single-link model using heightmap geometry for both the visual and collision. diff --git a/sdformat_test_files/models/geometry_mesh_scaled/model.config b/sdformat_test_files/models/geometry_mesh_scaled/model.config index 862436ed..5a2e8d01 100644 --- a/sdformat_test_files/models/geometry_mesh_scaled/model.config +++ b/sdformat_test_files/models/geometry_mesh_scaled/model.config @@ -10,5 +10,6 @@ + A single-link model using a mesh scaled differently on x, y, and z axes for both the visual and collision. diff --git a/sdformat_test_files/models/geometry_mesh_stl/model.config b/sdformat_test_files/models/geometry_mesh_stl/model.config index 3d884789..2b7bdf13 100644 --- a/sdformat_test_files/models/geometry_mesh_stl/model.config +++ b/sdformat_test_files/models/geometry_mesh_stl/model.config @@ -10,6 +10,6 @@ - Single link using an STL mesh. + A single-link model using an STL mesh. diff --git a/sdformat_test_files/models/geometry_plane/model.config b/sdformat_test_files/models/geometry_plane/model.config index d398d533..5cbfd6f6 100644 --- a/sdformat_test_files/models/geometry_plane/model.config +++ b/sdformat_test_files/models/geometry_plane/model.config @@ -10,6 +10,6 @@ - A plane using only the plane geometry type for both the visual and collision and a color. + A single-link model using the plane geometry type for both the visual and collision. diff --git a/sdformat_test_files/models/geometry_sphere/model.config b/sdformat_test_files/models/geometry_sphere/model.config index 9f9a8e2d..8b24ea1b 100644 --- a/sdformat_test_files/models/geometry_sphere/model.config +++ b/sdformat_test_files/models/geometry_sphere/model.config @@ -10,6 +10,6 @@ - A sphere using only the sphere geometry type for both the visual and collision and a color. + A single-link model using the sphere geometry type for both the visual and collision. diff --git a/sdformat_test_files/models/graph_chain/model.config b/sdformat_test_files/models/graph_chain/model.config index f59ae9f8..0454bef6 100644 --- a/sdformat_test_files/models/graph_chain/model.config +++ b/sdformat_test_files/models/graph_chain/model.config @@ -10,5 +10,6 @@ + A model having a chain of 3 links connected in series with revolute joints. diff --git a/sdformat_test_files/models/graph_chain_non_canonical_root/model.config b/sdformat_test_files/models/graph_chain_non_canonical_root/model.config index 3f14e419..1d44f5b0 100644 --- a/sdformat_test_files/models/graph_chain_non_canonical_root/model.config +++ b/sdformat_test_files/models/graph_chain_non_canonical_root/model.config @@ -10,5 +10,6 @@ + A model having a chain of 3 links connected in series with revolute joints, but the canonical link is not the root of the chain. diff --git a/sdformat_test_files/models/graph_four_bar/model.config b/sdformat_test_files/models/graph_four_bar/model.config index 72beaf1f..c12ffd3b 100644 --- a/sdformat_test_files/models/graph_four_bar/model.config +++ b/sdformat_test_files/models/graph_four_bar/model.config @@ -10,5 +10,6 @@ + A four-bar linkage made with four links connected by 4 revolute joints. diff --git a/sdformat_test_files/models/graph_loop/model.config b/sdformat_test_files/models/graph_loop/model.config index d1b69b5b..16df6225 100644 --- a/sdformat_test_files/models/graph_loop/model.config +++ b/sdformat_test_files/models/graph_loop/model.config @@ -10,5 +10,6 @@ + A model having three links connected by 3 joints to form a triangle. diff --git a/sdformat_test_files/models/graph_tree/model.config b/sdformat_test_files/models/graph_tree/model.config index d05248b9..7ef072fc 100644 --- a/sdformat_test_files/models/graph_tree/model.config +++ b/sdformat_test_files/models/graph_tree/model.config @@ -10,5 +10,6 @@ + A model with multiple links connected by joints forming a tree. diff --git a/sdformat_test_files/models/graph_tree_non_canonical_root/model.config b/sdformat_test_files/models/graph_tree_non_canonical_root/model.config index 0513776d..0cd5d51e 100644 --- a/sdformat_test_files/models/graph_tree_non_canonical_root/model.config +++ b/sdformat_test_files/models/graph_tree_non_canonical_root/model.config @@ -10,5 +10,6 @@ + A model with multiple links connected by joints forming a tree, but the canonical link is not the root of the tree. diff --git a/sdformat_test_files/models/joint_ball/model.config b/sdformat_test_files/models/joint_ball/model.config index 798ad13b..98f157f2 100644 --- a/sdformat_test_files/models/joint_ball/model.config +++ b/sdformat_test_files/models/joint_ball/model.config @@ -10,6 +10,6 @@ - Two links with a ball joint between them. + A model with two links connected by a ball joint. diff --git a/sdformat_test_files/models/joint_continuous/model.config b/sdformat_test_files/models/joint_continuous/model.config index ae44c7ec..fc713f2a 100644 --- a/sdformat_test_files/models/joint_continuous/model.config +++ b/sdformat_test_files/models/joint_continuous/model.config @@ -10,6 +10,6 @@ - Two links with a continuous joint between them. + A model with two links connected by a continuous joint. diff --git a/sdformat_test_files/models/joint_fixed/model.config b/sdformat_test_files/models/joint_fixed/model.config index b5b0faff..5387c2cc 100644 --- a/sdformat_test_files/models/joint_fixed/model.config +++ b/sdformat_test_files/models/joint_fixed/model.config @@ -10,6 +10,6 @@ - Two links with a fixed joint between them. + A model with two links connected by a fixed joint. diff --git a/sdformat_test_files/models/joint_gearbox/model.config b/sdformat_test_files/models/joint_gearbox/model.config index 0971c3b0..9b8c0aa7 100644 --- a/sdformat_test_files/models/joint_gearbox/model.config +++ b/sdformat_test_files/models/joint_gearbox/model.config @@ -10,6 +10,6 @@ - Two links connected to a reference link with revolute joints and a gearbox constraint. + A model with 3 links total. Two links are connected to a reference link with revolute joints and a gearbox joint enforces that one revolute joint rotates faster than the other. diff --git a/sdformat_test_files/models/joint_prismatic/model.config b/sdformat_test_files/models/joint_prismatic/model.config index f5407b43..6425ff80 100644 --- a/sdformat_test_files/models/joint_prismatic/model.config +++ b/sdformat_test_files/models/joint_prismatic/model.config @@ -10,6 +10,6 @@ - Two links with a prismatic joint between them + A model with two links connected by a prismatic joint. diff --git a/sdformat_test_files/models/joint_revolute/model.config b/sdformat_test_files/models/joint_revolute/model.config index 496f8bf6..3fcc1f61 100644 --- a/sdformat_test_files/models/joint_revolute/model.config +++ b/sdformat_test_files/models/joint_revolute/model.config @@ -10,6 +10,6 @@ - Two links with a revolute joint between them. + A model with two links connected by a revolute joint. diff --git a/sdformat_test_files/models/joint_revolute2/model.config b/sdformat_test_files/models/joint_revolute2/model.config index ef017b7a..8ca26adf 100644 --- a/sdformat_test_files/models/joint_revolute2/model.config +++ b/sdformat_test_files/models/joint_revolute2/model.config @@ -10,6 +10,6 @@ - Two links with a revolute 2 joint between them. + A model with two links connected by a revolute2 joint. diff --git a/sdformat_test_files/models/joint_revolute_axis/model.config b/sdformat_test_files/models/joint_revolute_axis/model.config index a60370cc..d9809e62 100644 --- a/sdformat_test_files/models/joint_revolute_axis/model.config +++ b/sdformat_test_files/models/joint_revolute_axis/model.config @@ -10,5 +10,6 @@ + A model with two links connected by a revolute joint with an axis having different values for x, y, and z. diff --git a/sdformat_test_files/models/joint_revolute_axis_in_frame/model.config b/sdformat_test_files/models/joint_revolute_axis_in_frame/model.config index 5032f5df..aa721773 100644 --- a/sdformat_test_files/models/joint_revolute_axis_in_frame/model.config +++ b/sdformat_test_files/models/joint_revolute_axis_in_frame/model.config @@ -10,5 +10,6 @@ + A model with two links connected by a revolute joint with an axis having different values for x, y, and z, and specified in a frame on the model. diff --git a/sdformat_test_files/models/joint_revolute_default_limits/model.config b/sdformat_test_files/models/joint_revolute_default_limits/model.config index eba0355a..55dc7bb7 100644 --- a/sdformat_test_files/models/joint_revolute_default_limits/model.config +++ b/sdformat_test_files/models/joint_revolute_default_limits/model.config @@ -10,5 +10,6 @@ + A model with two links connected by a revolute joint, having no joint limits specified on its axis. diff --git a/sdformat_test_files/models/joint_revolute_two_joints_two_links/model.config b/sdformat_test_files/models/joint_revolute_two_joints_two_links/model.config index 026a0a0a..cb70b395 100644 --- a/sdformat_test_files/models/joint_revolute_two_joints_two_links/model.config +++ b/sdformat_test_files/models/joint_revolute_two_joints_two_links/model.config @@ -10,5 +10,6 @@ + A model with two links connected by two revolute joints, effectively rigidly connecting the two. diff --git a/sdformat_test_files/models/joint_screw/model.config b/sdformat_test_files/models/joint_screw/model.config index e2b63451..fac45367 100644 --- a/sdformat_test_files/models/joint_screw/model.config +++ b/sdformat_test_files/models/joint_screw/model.config @@ -10,6 +10,6 @@ - Two links with a screw joint between them. + A model with two links connected by a screw joint. diff --git a/sdformat_test_files/models/joint_universal/model.config b/sdformat_test_files/models/joint_universal/model.config index 744fd61c..901c3107 100644 --- a/sdformat_test_files/models/joint_universal/model.config +++ b/sdformat_test_files/models/joint_universal/model.config @@ -10,6 +10,6 @@ - Two links with a universal joint between them. + A model with two links connected by a universal joint. diff --git a/sdformat_test_files/models/link_inertia/model.config b/sdformat_test_files/models/link_inertia/model.config index 6dc6359b..c8581db1 100644 --- a/sdformat_test_files/models/link_inertia/model.config +++ b/sdformat_test_files/models/link_inertia/model.config @@ -10,5 +10,6 @@ + A link having an inerta with a different value for each of it's 6 components. diff --git a/sdformat_test_files/models/link_light_point/model.config b/sdformat_test_files/models/link_light_point/model.config index c6200706..974fe4c0 100644 --- a/sdformat_test_files/models/link_light_point/model.config +++ b/sdformat_test_files/models/link_light_point/model.config @@ -10,5 +10,6 @@ + A model with a single link having a point light attached to it.
diff --git a/sdformat_test_files/models/link_multiple_collisions/model.config b/sdformat_test_files/models/link_multiple_collisions/model.config index 2923b8d8..836c5eb4 100644 --- a/sdformat_test_files/models/link_multiple_collisions/model.config +++ b/sdformat_test_files/models/link_multiple_collisions/model.config @@ -10,5 +10,6 @@ + A model with a single link having multiple collision elements on it. diff --git a/sdformat_test_files/models/link_multiple_visuals/model.config b/sdformat_test_files/models/link_multiple_visuals/model.config index 6ccb0ce5..d55e38bb 100644 --- a/sdformat_test_files/models/link_multiple_visuals/model.config +++ b/sdformat_test_files/models/link_multiple_visuals/model.config @@ -10,5 +10,6 @@ + A model with a single link having multile visual elements on it. diff --git a/sdformat_test_files/models/link_sensor_imu/model.config b/sdformat_test_files/models/link_sensor_imu/model.config index 4123a292..121df1db 100644 --- a/sdformat_test_files/models/link_sensor_imu/model.config +++ b/sdformat_test_files/models/link_sensor_imu/model.config @@ -10,5 +10,6 @@ + A model with a single link having an IMU sensor attached to it. diff --git a/sdformat_test_files/models/material_blinn_phong/model.config b/sdformat_test_files/models/material_blinn_phong/model.config index 3ae9e89a..65215b31 100644 --- a/sdformat_test_files/models/material_blinn_phong/model.config +++ b/sdformat_test_files/models/material_blinn_phong/model.config @@ -10,6 +10,6 @@ - Single link using ambient/diffuse/specular/emissive components to color it. + A single link with a material that uses ambient/diffuse/specular/emissive components to color it. diff --git a/sdformat_test_files/models/material_dynamic_lights/model.config b/sdformat_test_files/models/material_dynamic_lights/model.config index 66a1a865..91cdc76e 100644 --- a/sdformat_test_files/models/material_dynamic_lights/model.config +++ b/sdformat_test_files/models/material_dynamic_lights/model.config @@ -10,6 +10,6 @@ - Two visuals: one with dynamic lights on, another with dynamic lights off. + A link with two visuals: one with dynamic lights on, and the other with dynamic lights off. diff --git a/sdformat_test_files/models/model_two_models/model.config b/sdformat_test_files/models/model_two_models/model.config index 05bbe2c6..896cdcb2 100644 --- a/sdformat_test_files/models/model_two_models/model.config +++ b/sdformat_test_files/models/model_two_models/model.config @@ -10,5 +10,6 @@ + An SDFormat XML file having two models in it. diff --git a/sdformat_test_files/models/model_zero_models/model.config b/sdformat_test_files/models/model_zero_models/model.config index da3fa4c7..74d60021 100644 --- a/sdformat_test_files/models/model_zero_models/model.config +++ b/sdformat_test_files/models/model_zero_models/model.config @@ -10,5 +10,6 @@ + An SDFormat XML file that does not have a model in it. diff --git a/sdformat_test_files/models/pose_chain/model.config b/sdformat_test_files/models/pose_chain/model.config index 58337375..9c386b25 100644 --- a/sdformat_test_files/models/pose_chain/model.config +++ b/sdformat_test_files/models/pose_chain/model.config @@ -10,5 +10,6 @@ + A chain of links connected by joints, where every link and joint in the chain has a non-zero pose. diff --git a/sdformat_test_files/models/pose_collision/model.config b/sdformat_test_files/models/pose_collision/model.config index f38bb20a..668717a9 100644 --- a/sdformat_test_files/models/pose_collision/model.config +++ b/sdformat_test_files/models/pose_collision/model.config @@ -10,5 +10,6 @@ + A single-link model where only the collision has a non-zero pose. diff --git a/sdformat_test_files/models/pose_collision_in_frame/model.config b/sdformat_test_files/models/pose_collision_in_frame/model.config index 86c7e88f..2bdda06e 100644 --- a/sdformat_test_files/models/pose_collision_in_frame/model.config +++ b/sdformat_test_files/models/pose_collision_in_frame/model.config @@ -10,5 +10,6 @@ + A single-link model where only the collision has a non-zero pose, and that pose is given in a frame on the model. diff --git a/sdformat_test_files/models/pose_inertial/model.config b/sdformat_test_files/models/pose_inertial/model.config index 0fdd7ab2..ab608588 100644 --- a/sdformat_test_files/models/pose_inertial/model.config +++ b/sdformat_test_files/models/pose_inertial/model.config @@ -10,5 +10,6 @@ + A single-link model where only the inertial has a non-zero pose. diff --git a/sdformat_test_files/models/pose_inertial_in_frame/model.config b/sdformat_test_files/models/pose_inertial_in_frame/model.config index e383183e..d059c030 100644 --- a/sdformat_test_files/models/pose_inertial_in_frame/model.config +++ b/sdformat_test_files/models/pose_inertial_in_frame/model.config @@ -10,5 +10,6 @@ + A single-link model where only the inertial has a non-zero pose, and that pose is given in a frame on the model. diff --git a/sdformat_test_files/models/pose_joint/model.config b/sdformat_test_files/models/pose_joint/model.config index 8b43f0b1..202290c1 100644 --- a/sdformat_test_files/models/pose_joint/model.config +++ b/sdformat_test_files/models/pose_joint/model.config @@ -10,5 +10,6 @@ + A model having two links and a revolute joint, where only the joint has a non-zero pose. diff --git a/sdformat_test_files/models/pose_joint_in_frame/model.config b/sdformat_test_files/models/pose_joint_in_frame/model.config index 45e04007..086a770e 100644 --- a/sdformat_test_files/models/pose_joint_in_frame/model.config +++ b/sdformat_test_files/models/pose_joint_in_frame/model.config @@ -10,5 +10,6 @@ + A model having two links and a revolute joint, where only the joint has a non-zero pose, and that pose is given in a frame on the model. diff --git a/sdformat_test_files/models/pose_link/model.config b/sdformat_test_files/models/pose_link/model.config index 68368ef8..5342a567 100644 --- a/sdformat_test_files/models/pose_link/model.config +++ b/sdformat_test_files/models/pose_link/model.config @@ -10,5 +10,6 @@ + A single-link model where only the link has a non-zero pose. diff --git a/sdformat_test_files/models/pose_link_all/model.config b/sdformat_test_files/models/pose_link_all/model.config index a637e8df..054550f0 100644 --- a/sdformat_test_files/models/pose_link_all/model.config +++ b/sdformat_test_files/models/pose_link_all/model.config @@ -10,5 +10,6 @@ + A single-link model where the link, visual, collision, and inertial elements all have poses. diff --git a/sdformat_test_files/models/pose_link_in_frame/model.config b/sdformat_test_files/models/pose_link_in_frame/model.config index eb811cfa..491f458a 100644 --- a/sdformat_test_files/models/pose_link_in_frame/model.config +++ b/sdformat_test_files/models/pose_link_in_frame/model.config @@ -10,5 +10,6 @@ + A single-link model where only the link has a non-zero pose, and that pose is given in a frame on the model. diff --git a/sdformat_test_files/models/pose_model/model.config b/sdformat_test_files/models/pose_model/model.config index c500ee24..e96328f3 100644 --- a/sdformat_test_files/models/pose_model/model.config +++ b/sdformat_test_files/models/pose_model/model.config @@ -10,5 +10,6 @@ + A single-link model where the model itself has a non-zero pose. diff --git a/sdformat_test_files/models/pose_visual/model.config b/sdformat_test_files/models/pose_visual/model.config index a2186fa5..71fed64a 100644 --- a/sdformat_test_files/models/pose_visual/model.config +++ b/sdformat_test_files/models/pose_visual/model.config @@ -10,5 +10,6 @@ + A single-link model where only the visual has a non-zero pose. diff --git a/sdformat_test_files/models/pose_visual_in_frame/model.config b/sdformat_test_files/models/pose_visual_in_frame/model.config index d57d05a9..0721e14d 100644 --- a/sdformat_test_files/models/pose_visual_in_frame/model.config +++ b/sdformat_test_files/models/pose_visual_in_frame/model.config @@ -10,5 +10,6 @@ + A single-link model where only the visual has a non-zero pose, and that pose is given in a frame on the model. From c0c29e281c4726bd9c013d13b4434003ee598583 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 13 Oct 2020 15:14:41 -0700 Subject: [PATCH 120/152] Add sdformat_test_files README Signed-off-by: Shane Loretz --- sdformat_test_files/README.md | 127 ++++++++++++++++++++ sdformat_test_files/_scripts/README.md.in | 33 +++++ sdformat_test_files/_scripts/make_readme.py | 60 +++++++++ 3 files changed, 220 insertions(+) create mode 100644 sdformat_test_files/README.md create mode 100644 sdformat_test_files/_scripts/README.md.in create mode 100644 sdformat_test_files/_scripts/make_readme.py diff --git a/sdformat_test_files/README.md b/sdformat_test_files/README.md new file mode 100644 index 00000000..460c18ee --- /dev/null +++ b/sdformat_test_files/README.md @@ -0,0 +1,127 @@ +# SDFormat Test files + +This package contains a list of SDFormat files for testing tools that work with SDFormat XML. + +## Models + +### Geometry + +* `geometry_box` + * A single-link model using the box geometry type for both the visual and collision. +* `geometry_cylinder` + * A single-link model using the cylinder geometry type for both the visual and collision. +* `geometry_heightmap` + * A single-link model using heightmap geometry for both the visual and collision. +* `geometry_mesh_collada` + * A single link using mesh geometry with a COLLADA mesh. +* `geometry_mesh_obj` + * A single link using a Wavefront OBJ mesh. +* `geometry_mesh_scaled` + * A single-link model using a mesh scaled differently on x, y, and z axes for both the visual and collision. +* `geometry_mesh_stl` + * A single-link model using an STL mesh. +* `geometry_plane` + * A single-link model using the plane geometry type for both the visual and collision. +* `geometry_sphere` + * A single-link model using the sphere geometry type for both the visual and collision. + +### Materials + +* `material_blinn_phong` + * A single link with a material that uses ambient/diffuse/specular/emissive components to color it. +* `material_dynamic_lights` + * A link with two visuals: one with dynamic lights on, and the other with dynamic lights off. + +### Joints + +* `joint_ball` + * A model with two links connected by a ball joint. +* `joint_continuous` + * A model with two links connected by a continuous joint. +* `joint_fixed` + * A model with two links connected by a fixed joint. +* `joint_gearbox` + * A model with 3 links total. Two links are connected to a reference link with revolute joints and a gearbox joint enforces that one revolute joint rotates faster than the other. +* `joint_prismatic` + * A model with two links connected by a prismatic joint. +* `joint_revolute` + * A model with two links connected by a revolute joint. +* `joint_revolute2` + * A model with two links connected by a revolute2 joint. +* `joint_revolute_axis` + * A model with two links connected by a revolute joint with an axis having different values for x, y, and z. +* `joint_revolute_axis_in_frame` + * A model with two links connected by a revolute joint with an axis having different values for x, y, and z, and specified in a frame on the model. +* `joint_revolute_default_limits` + * A model with two links connected by a revolute joint, having no joint limits specified on its axis. +* `joint_revolute_two_joints_two_links` + * A model with two links connected by two revolute joints, effectively rigidly connecting the two. +* `joint_screw` + * A model with two links connected by a screw joint. +* `joint_universal` + * A model with two links connected by a universal joint. + +### Links + +* `link_inertia` + * A link having an inerta with a different value for each of it's 6 components. +* `link_light_point` + * A model with a single link having a point light attached to it. +* `link_multiple_collisions` + * A model with a single link having multiple collision elements on it. +* `link_multiple_visuals` + * A model with a single link having multile visual elements on it. +* `link_sensor_imu` + * A model with a single link having an IMU sensor attached to it. + +### Kinematic structures + +* `graph_chain` + * A model having a chain of 3 links connected in series with revolute joints. +* `graph_chain_non_canonical_root` + * A model having a chain of 3 links connected in series with revolute joints, but the canonical link is not the root of the chain. +* `graph_four_bar` + * A four-bar linkage made with four links connected by 4 revolute joints. +* `graph_loop` + * A model having three links connected by 3 joints to form a triangle. +* `graph_tree` + * A model with multiple links connected by joints forming a tree. +* `graph_tree_non_canonical_root` + * A model with multiple links connected by joints forming a tree, but the canonical link is not the root of the tree. + +### Poses and Frames + +* `pose_chain` + * A chain of links connected by joints, where every link and joint in the chain has a non-zero pose. +* `pose_collision` + * A single-link model where only the collision has a non-zero pose. +* `pose_collision_in_frame` + * A single-link model where only the collision has a non-zero pose, and that pose is given in a frame on the model. +* `pose_inertial` + * A single-link model where only the inertial has a non-zero pose. +* `pose_inertial_in_frame` + * A single-link model where only the inertial has a non-zero pose, and that pose is given in a frame on the model. +* `pose_joint` + * A model having two links and a revolute joint, where only the joint has a non-zero pose. +* `pose_joint_in_frame` + * A model having two links and a revolute joint, where only the joint has a non-zero pose, and that pose is given in a frame on the model. +* `pose_link` + * A single-link model where only the link has a non-zero pose. +* `pose_link_all` + * A single-link model where the link, visual, collision, and inertial elements all have poses. +* `pose_link_in_frame` + * A single-link model where only the link has a non-zero pose, and that pose is given in a frame on the model. +* `pose_model` + * A single-link model where the model itself has a non-zero pose. +* `pose_visual` + * A single-link model where only the visual has a non-zero pose. +* `pose_visual_in_frame` + * A single-link model where only the visual has a non-zero pose, and that pose is given in a frame on the model. + +### Models + +* `model_two_models` + * An SDFormat XML file having two models in it. +* `model_zero_models` + * An SDFormat XML file that does not have a model in it. + diff --git a/sdformat_test_files/_scripts/README.md.in b/sdformat_test_files/_scripts/README.md.in new file mode 100644 index 00000000..73f305ef --- /dev/null +++ b/sdformat_test_files/_scripts/README.md.in @@ -0,0 +1,33 @@ +# SDFormat Test files + +This package contains a list of SDFormat files for testing tools that work with SDFormat XML. + +## Models + +### Geometry + +$geometry + +### Materials + +$materials + +### Joints + +$joints + +### Links + +$links + +### Kinematic structures + +$graphs + +### Poses and Frames + +$poses + +### Models + +$models diff --git a/sdformat_test_files/_scripts/make_readme.py b/sdformat_test_files/_scripts/make_readme.py new file mode 100644 index 00000000..ab6ecf01 --- /dev/null +++ b/sdformat_test_files/_scripts/make_readme.py @@ -0,0 +1,60 @@ +import string +import os +import xml.etree.ElementTree as ET + + +def get_model_name_and_description(path_to_model_dir): + tree = ET.parse(os.path.join(path_to_model_dir, 'model.config')) + root = tree.getroot() + name = root.findall('name')[0].text.strip() + description = root.findall('description')[0].text.strip() + return (name, description) + + +def models_in_dir(path_to_dir): + for path in os.listdir(path_to_dir): + abspath = os.path.abspath(os.path.join(path_to_dir, path)) + if os.path.isdir(abspath) and os.path.isfile(os.path.join(abspath, 'model.config')): + yield abspath + + +if __name__ == '__main__': + this_dir = os.path.abspath(os.path.dirname(__file__)) + models_dir = os.path.join(this_dir, '..', 'models') + + template_mapping = { + 'geometry': [], + 'materials': [], + 'joints': [], + 'links': [], + 'graphs': [], + 'poses': [], + 'models': [] + } + + for model_path in sorted(models_in_dir(models_dir)): + name, desc = get_model_name_and_description(model_path) + entry = f'* `{name}`\n * {desc}' + if name.startswith('geometry'): + template_mapping['geometry'].append(entry) + elif name.startswith('material'): + template_mapping['materials'].append(entry) + elif name.startswith('joint'): + template_mapping['joints'].append(entry) + elif name.startswith('link'): + template_mapping['links'].append(entry) + elif name.startswith('graph'): + template_mapping['graphs'].append(entry) + elif name.startswith('pose'): + template_mapping['poses'].append(entry) + elif name.startswith('model'): + template_mapping['models'].append(entry) + else: + raise RuntimeError(f'Unknown model type {name} at {model_path}') + + for key in template_mapping.keys(): + template_mapping[key] = '\n'.join(template_mapping[key]) + + with open(os.path.join(this_dir, 'README.md.in'), 'r') as fin: + template = string.Template(fin.read()) + print(template.substitute(template_mapping)) From 4805f385114cdcc40a550f01db10d7777f04e4d9 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 13 Oct 2020 16:33:05 -0700 Subject: [PATCH 121/152] Add README for sdformat_urdf Signed-off-by: Shane Loretz --- sdformat_urdf/README.md | 56 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) create mode 100644 sdformat_urdf/README.md diff --git a/sdformat_urdf/README.md b/sdformat_urdf/README.md new file mode 100644 index 00000000..c4ed4bc2 --- /dev/null +++ b/sdformat_urdf/README.md @@ -0,0 +1,56 @@ +# SDFormat URDF + +This package contains a C++ library and `urdf_parser_plugin` for converting SDFormat XML into URDF C++ structures. +Installing it allows one to use SDFormat XML instead of URDF XML as a robot description. + +## Supported platforms + +The package has been tested with ROS Rolling Ridley on Ubuntu Focal. + +## Limitations and Considerations + +In general, URDF C++ structures cannot represent every possible SDFormat XML file. +SDFormat XML used with this plugin must be constructed with the following limitations. + +### Limitations that result in Errors + +This package will error and refuse to convert any SDFormat XML that violates these constraints. + +#### Model limitations +* The XML file must contain a single `` not in a ``. +* The `` tag must not have a `` tag. +* There must not be any nested `` tags. + +#### Geometry limitations +* The only supported geometry types are ``, ``, ``, and `sphere`. +* The model must not use `` or ``. + +#### Joint limitations +* The only supported joint types are `continuous`, `fixed`, `prismatic`, and `revolute`. +* The model must not use `universal`, `screw`, `revolute2`, `gearbox`, or `ball` joints. + +#### Kinematic limitations +* Starting from the canonical link, the links and joints must form a tree. +* No link may be a child of more than 1 joint +* The canonical link cannot be a child of any joint + +### Limitations that may result in Warnings + +If any of these constraints are voilated then the library may issue a console warning, but the model is still converted to URDF c++ structures. +The warning is issued using an `rcutils` logger with the name `sdformat_urdf`. + +#### Joint limitations +* `` elements should not use `` +* `` elements should not use `` or `` +* `` elements should not use `` or `` +* `` elements should not use `` or `` + +#### Link limitations +* The link should not have any `` tags. +* The link should not have any `` tags. + +#### Material limitations +* Only solid color materials are supported - the color of the urdf comes from the `` tag of the model +* The model should not disable dynamic lighting using the `` +* The model should not use materials with `