Skip to content

Commit

Permalink
additional fix
Browse files Browse the repository at this point in the history
  • Loading branch information
EricCousineau-TRI committed Jun 21, 2023
1 parent d1c7fad commit 7ea12a5
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 7 deletions.
1 change: 0 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
bazel-*
/.vscode/

# User-specified configuration
/bazel_ros2_rules/user.bazelrc
Expand Down
8 changes: 2 additions & 6 deletions drake_ros/core/geometry_conversions_pybind.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include "ros_idl_pybind.h"
#pragma once

namespace PYBIND11_NAMESPACE {
namespace detail {
#include "ros_idl_pybind.h"

// Generic typecaster for specific ROS 2 messages.
// This method can be used instead of the ROS_MSG_PYBIND_TYPECAST_ALL() macro.
Expand All @@ -13,6 +12,3 @@ ROS_MSG_PYBIND_TYPECAST(geometry_msgs::msg::Accel);
ROS_MSG_PYBIND_TYPECAST(geometry_msgs::msg::Wrench);
ROS_MSG_PYBIND_TYPECAST(geometry_msgs::msg::Pose);
ROS_MSG_PYBIND_TYPECAST(geometry_msgs::msg::Transform);

} // namespace detail
} // namespace PYBIND11_NAMESPACE
2 changes: 2 additions & 0 deletions drake_ros/core/ros_idl_pybind.h
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#pragma once

#include <regex>
#include <string>
#include <type_traits>
Expand Down

0 comments on commit 7ea12a5

Please sign in to comment.