Skip to content

Commit

Permalink
Update urdf/model.h -> urdf/model.hpp (#3003)
Browse files Browse the repository at this point in the history
Co-authored-by: Sebastian Castro <[email protected]>
Co-authored-by: Sebastian Jahr <[email protected]>
  • Loading branch information
3 people authored Oct 11, 2024
1 parent b88af32 commit 9f00fd0
Show file tree
Hide file tree
Showing 6 changed files with 22 additions and 2 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ jobs:
# TODO(andyz): When this clang-tidy issue is fixed, remove -Wno-unknown-warning-option
# https://stackoverflow.com/a/41673702
CXXFLAGS: >-
-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unknown-warning-option
-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unknown-warning-option -Wno-cpp
CLANG_TIDY_ARGS: --fix --fix-errors --format-style=file
DOCKER_IMAGE: moveit/moveit2:${{ matrix.env.IMAGE }}
UPSTREAM_WORKSPACE: >
Expand Down
4 changes: 4 additions & 0 deletions moveit_core/constraint_samplers/test/pr2_arm_ik.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,11 @@
#pragma once

#include <urdf_model/model.h>
#if __has_include(<urdf/model.hpp>)
#include <urdf/model.hpp>
#else
#include <urdf/model.h>
#endif
#include <Eigen/Geometry>
#include <Eigen/LU> // provides LU decomposition
#include <kdl/chainiksolver.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,11 @@

#include <kdl/chainfksolverpos_recursive.hpp>

#if __has_include(<urdf/model.hpp>)
#include <urdf/model.hpp>
#else
#include <urdf/model.h>
#endif

#include <moveit/kinematics_base/kinematics_base.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,11 @@
#pragma once

#include <srdfdom/srdf_writer.h>
#if __has_include(<urdf/model.hpp>)
#include <urdf/model.hpp>
#else
#include <urdf/model.h>
#endif
#include <moveit/robot_model/robot_model.h>
#include <geometry_msgs/msg/pose.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,11 @@

#include <moveit/macros/class_forward.h>
#include <moveit/rdf_loader/synchronized_string_parameter.h>
#if __has_include(<urdf/model.hpp>)
#include <urdf/model.hpp>
#else
#include <urdf/model.h>
#endif
#include <srdfdom/model.h>
#include <rclcpp/rclcpp.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,11 @@
#pragma once

#include <moveit_setup_framework/config.hpp>
#include <urdf/model.h> // for testing a valid urdf is loaded
#if __has_include(<urdf/model.hpp>) // for testing a valid urdf is loaded
#include <urdf/model.hpp>
#else
#include <urdf/model.h>
#endif

namespace moveit_setup
{
Expand Down

0 comments on commit 9f00fd0

Please sign in to comment.