Skip to content

Commit

Permalink
Fix build and tests with Humble and Rolling (#12)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina authored Jun 6, 2022
1 parent 785d752 commit d3d8eb4
Show file tree
Hide file tree
Showing 12 changed files with 50 additions and 49 deletions.
6 changes: 3 additions & 3 deletions sdformat_urdf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ find_package(ament_cmake_ros REQUIRED)

find_package(pluginlib REQUIRED)
find_package(rcutils REQUIRED)
find_package(sdformat9 REQUIRED)
find_package(sdformat12 REQUIRED)
find_package(urdfdom_headers 1.0.6 REQUIRED)
find_package(urdf_parser_plugin REQUIRED)
find_package(tinyxml2_vendor REQUIRED)
Expand All @@ -25,7 +25,7 @@ add_library(sdformat_urdf SHARED
src/sdformat_urdf.cpp
)
target_link_libraries(sdformat_urdf PUBLIC
sdformat9::sdformat9
sdformat12::sdformat12
urdfdom_headers::urdfdom_headers
)
target_link_libraries(sdformat_urdf PRIVATE
Expand All @@ -51,7 +51,7 @@ target_link_libraries(sdformat_urdf_plugin PRIVATE

ament_export_dependencies(pluginlib)
ament_export_dependencies(rcutils)
ament_export_dependencies(sdformat9)
ament_export_dependencies(sdformat12)
ament_export_dependencies(tinyxml2)
ament_export_dependencies(urdf_parser_plugin)
ament_export_dependencies(urdfdom_headers)
Expand Down
5 changes: 4 additions & 1 deletion sdformat_urdf/include/sdformat_urdf/sdformat_urdf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,15 @@
#ifndef SDFORMAT_URDF__SDFORMAT_URDF_HPP_
#define SDFORMAT_URDF__SDFORMAT_URDF_HPP_

#include <sdf/sdf.hh>
#include <urdf_world/types.h>
#include <urdf_model/types.h>

#include <string>

#include <sdf/Model.hh>
#include <sdf/Root.hh>
#include <sdf/Types.hh>

#include "sdformat_urdf/visibility_control.hpp"

namespace sdformat_urdf
Expand Down
2 changes: 1 addition & 1 deletion sdformat_urdf/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_export_depend>ament_cmake_ros</buildtool_export_depend>

<depend>sdformat</depend>
<depend>sdformat12</depend>
<depend>urdf</depend>

<build_depend>liburdfdom-headers-dev</build_depend>
Expand Down
25 changes: 13 additions & 12 deletions sdformat_urdf/src/sdformat_urdf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <ignition/math/Pose3.hh>
#include <rcutils/logging_macros.h>
#include <sdf/sdf.hh>
#include <urdf_world/types.h>
#include <urdf_model/model.h>

Expand All @@ -23,6 +21,16 @@
#include <string>
#include <vector>

#include <ignition/math/Pose3.hh>
#include <sdf/Error.hh>
#include <sdf/Collision.hh>
#include <sdf/Geometry.hh>
#include <sdf/Joint.hh>
#include <sdf/JointAxis.hh>
#include <sdf/Link.hh>
#include <sdf/Mesh.hh>
#include <sdf/Visual.hh>

#include "sdformat_urdf/sdformat_urdf.hpp"

namespace sdformat_urdf
Expand Down Expand Up @@ -66,20 +74,13 @@ 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()) {
if (nullptr == sdf_dom.Model()) {
errors.emplace_back(
sdf::ErrorCode::STRING_READ,
sdf::ErrorCode::ELEMENT_MISSING,
"SDFormat xml has no models; need at least one");
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);
return convert_model(*sdf_dom.Model(), errors);
}

urdf::ModelInterfaceSharedPtr
Expand Down
5 changes: 3 additions & 2 deletions sdformat_urdf/test/geometry_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,11 @@


#include <gtest/gtest.h>
#include <sdf/sdf.hh>
#include <sdformat_urdf/sdformat_urdf.hpp>
#include <urdf_model/model.h>
#include <urdf_model/types.h>
#include <sdformat_urdf/sdformat_urdf.hpp>

#include <sdf/Types.hh>

#include "sdf_paths.hpp"
#include "test_tools.hpp"
Expand Down
5 changes: 3 additions & 2 deletions sdformat_urdf/test/graph_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,11 @@


#include <gtest/gtest.h>
#include <sdf/sdf.hh>
#include <sdformat_urdf/sdformat_urdf.hpp>
#include <urdf_model/model.h>
#include <urdf_model/types.h>
#include <sdformat_urdf/sdformat_urdf.hpp>

#include <sdf/Types.hh>

#include "sdf_paths.hpp"
#include "test_tools.hpp"
Expand Down
12 changes: 1 addition & 11 deletions sdformat_urdf/test/include/test_tools.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,6 @@
#ifndef TEST_TOOLS_HPP_
#define TEST_TOOLS_HPP_

#include <sdf/sdf.hh>

#include <algorithm>
#include <string>
#include <fstream>
Expand Down Expand Up @@ -60,7 +58,7 @@ get_file(const char * path)
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) { \
if (*expected_name_iter == child->name) { \
name_is_expected = true; \
expected_names.erase(expected_name_iter); \
break; \
Expand All @@ -81,12 +79,4 @@ get_file(const char * path)
} \
} 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_
17 changes: 9 additions & 8 deletions sdformat_urdf/test/joint_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,11 @@


#include <gtest/gtest.h>
#include <sdf/sdf.hh>
#include <sdformat_urdf/sdformat_urdf.hpp>
#include <urdf_model/model.h>
#include <urdf_model/types.h>
#include <sdformat_urdf/sdformat_urdf.hpp>

#include <sdf/Types.hh>

#include "sdf_paths.hpp"
#include "test_tools.hpp"
Expand Down Expand Up @@ -112,8 +113,8 @@ TEST(Joint, joint_prismatic)
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
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), joint->limits->effort);
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), joint->limits->velocity);
ASSERT_EQ(nullptr, joint->safety);
ASSERT_EQ(nullptr, joint->calibration);
ASSERT_EQ(nullptr, joint->mimic);
Expand All @@ -139,8 +140,8 @@ TEST(Joint, joint_revolute)
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
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), joint->limits->effort);
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), joint->limits->velocity);
ASSERT_EQ(nullptr, joint->safety);
ASSERT_EQ(nullptr, joint->calibration);
ASSERT_EQ(nullptr, joint->mimic);
Expand Down Expand Up @@ -224,8 +225,8 @@ TEST(Joint, joint_revolute_default_limits)
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
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), joint->limits->effort);
EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), joint->limits->velocity);
}

TEST(Joint, joint_revolute_two_joints_two_links)
Expand Down
5 changes: 3 additions & 2 deletions sdformat_urdf/test/link_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,11 @@


#include <gtest/gtest.h>
#include <sdf/sdf.hh>
#include <sdformat_urdf/sdformat_urdf.hpp>
#include <urdf_model/model.h>
#include <urdf_model/types.h>
#include <sdformat_urdf/sdformat_urdf.hpp>

#include <sdf/Types.hh>

#include "sdf_paths.hpp"
#include "test_tools.hpp"
Expand Down
5 changes: 3 additions & 2 deletions sdformat_urdf/test/material_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,11 @@


#include <gtest/gtest.h>
#include <sdf/sdf.hh>
#include <sdformat_urdf/sdformat_urdf.hpp>
#include <urdf_model/model.h>
#include <urdf_model/types.h>
#include <sdformat_urdf/sdformat_urdf.hpp>

#include <sdf/Types.hh>

#include "sdf_paths.hpp"
#include "test_tools.hpp"
Expand Down
5 changes: 3 additions & 2 deletions sdformat_urdf/test/model_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,11 @@


#include <gtest/gtest.h>
#include <sdf/sdf.hh>
#include <sdformat_urdf/sdformat_urdf.hpp>
#include <urdf_model/model.h>
#include <urdf_model/types.h>
#include <sdformat_urdf/sdformat_urdf.hpp>

#include <sdf/Types.hh>

#include "sdf_paths.hpp"
#include "test_tools.hpp"
Expand Down
7 changes: 4 additions & 3 deletions sdformat_urdf/test/pose_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,12 @@


#include <gtest/gtest.h>
#include <ignition/math/Pose3.hh>
#include <sdf/sdf.hh>
#include <sdformat_urdf/sdformat_urdf.hpp>
#include <urdf_model/model.h>
#include <urdf_model/types.h>
#include <sdformat_urdf/sdformat_urdf.hpp>

#include <ignition/math/Pose3.hh>
#include <sdf/Types.hh>

#include "sdf_paths.hpp"
#include "test_tools.hpp"
Expand Down

0 comments on commit d3d8eb4

Please sign in to comment.