From a0878b3337ab888a2e3ee16ecc4dc59d562f5475 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 5 Jun 2023 15:58:46 +0300 Subject: [PATCH 01/28] feat: create autoware_auto_msgs_adapter node MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_auto_msgs_adapter/CMakeLists.txt | 27 ++++++ .../autoware_auto_msgs_adapter/README.md | 1 + .../autoware_auto_msgs_adapter.param.yaml | 3 + .../autoware_auto_msgs_adapter_core.hpp | 89 +++++++++++++++++++ .../autoware_auto_msgs_adapter.launch.xml | 8 ++ .../autoware_auto_msgs_adapter/package.xml | 27 ++++++ .../src/autoware_auto_msgs_adapter_core.cpp | 45 ++++++++++ .../test/test_1.cpp | 21 +++++ .../test/test_autoware_auto_msgs_adapter.cpp | 25 ++++++ 9 files changed, 246 insertions(+) create mode 100644 simulator/autoware_auto_msgs_adapter/CMakeLists.txt create mode 100644 simulator/autoware_auto_msgs_adapter/README.md create mode 100644 simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml create mode 100644 simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp create mode 100755 simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml create mode 100644 simulator/autoware_auto_msgs_adapter/package.xml create mode 100644 simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp create mode 100644 simulator/autoware_auto_msgs_adapter/test/test_1.cpp create mode 100644 simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp diff --git a/simulator/autoware_auto_msgs_adapter/CMakeLists.txt b/simulator/autoware_auto_msgs_adapter/CMakeLists.txt new file mode 100644 index 0000000000000..2b95f80f8681f --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_auto_msgs_adapter) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +set(NODE_NAME ${PROJECT_NAME}_node) +set(EXEC_NAME ${PROJECT_NAME}_exe) +set(TEST_NAME test_${PROJECT_NAME}) + +ament_auto_add_library(${NODE_NAME} SHARED + src/autoware_auto_msgs_adapter_core.cpp + include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp) + +rclcpp_components_register_node(${NODE_NAME} + PLUGIN "autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode" + EXECUTABLE ${EXEC_NAME}) + +if(BUILD_TESTING) + file(GLOB_RECURSE FILES_TEST test/*.cpp) + ament_add_ros_isolated_gtest(${TEST_NAME} ${FILES_TEST}) + target_link_libraries(${TEST_NAME} ${NODE_NAME}) +endif() + +ament_auto_package(INSTALL_TO_SHARE + launch + config) diff --git a/simulator/autoware_auto_msgs_adapter/README.md b/simulator/autoware_auto_msgs_adapter/README.md new file mode 100644 index 0000000000000..3e9eed2112275 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/README.md @@ -0,0 +1 @@ +# autoware_auto_msgs_adapter diff --git a/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml b/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml new file mode 100644 index 0000000000000..3f753f5ce0019 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + test: 123 diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp new file mode 100644 index 0000000000000..8edf7564bd0a3 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp @@ -0,0 +1,89 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ + +#include +#include + +#include +#include + +/// custom_type: autoware_control_msgs::msg::Control +/// ros_message_type: autoware_auto_control_msgs::msg::AckermannControlCommand +template <> +struct rclcpp::TypeAdapter< + autoware_control_msgs::msg::Control, autoware_auto_control_msgs::msg::AckermannControlCommand> +{ + using is_specialized = std::true_type; + using custom_type = autoware_control_msgs::msg::Control; + using ros_message_type = autoware_auto_control_msgs::msg::AckermannControlCommand; + + /// \brief Convert from custom type to ROS message type. Will be used when subscribing to a + /// autoware_auto_control_msgs::msg::AckermannControlCommand topic. + static void convert_to_ros_message(const custom_type & source, ros_message_type & destination) + { + destination.stamp = source.stamp; + + const auto & lateral_auto = source.lateral; + auto & lateral = destination.lateral; + lateral.stamp = lateral_auto.stamp; + lateral.steering_tire_angle = lateral_auto.steering_tire_angle; + lateral.steering_tire_rotation_rate = lateral_auto.steering_tire_rotation_rate; + + const auto & longitudinal_auto = source.longitudinal; + auto & longitudinal = destination.longitudinal; + longitudinal.stamp = longitudinal_auto.stamp; + longitudinal.acceleration = longitudinal_auto.acceleration; + longitudinal.jerk = longitudinal_auto.jerk; + longitudinal.speed = longitudinal_auto.velocity; + } + + static void convert_to_custom(const ros_message_type & source, custom_type & destination) + { + destination.stamp = source.stamp; + + const auto & lateral = source.lateral; + auto & lateral_auto = destination.lateral; + lateral_auto.stamp = lateral.stamp; + lateral_auto.steering_tire_angle = lateral.steering_tire_angle; + lateral_auto.steering_tire_rotation_rate = lateral.steering_tire_rotation_rate; + + const auto & longitudinal = source.longitudinal; + auto & longitudinal_auto = destination.longitudinal; + longitudinal_auto.stamp = longitudinal.stamp; + longitudinal_auto.acceleration = longitudinal.acceleration; + longitudinal_auto.jerk = longitudinal.jerk; + longitudinal_auto.velocity = longitudinal.speed; + } +}; + +namespace autoware_auto_msgs_adapter +{ +using autoware_auto_control_msgs::msg::AckermannControlCommand; +using autoware_control_msgs::msg::Control; + +using Adapter = rclcpp::TypeAdapter; +class AutowareAutoMsgsAdapterNode : public rclcpp::Node +{ +public: + explicit AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptions & node_options); + +private: + rclcpp::Subscription::SharedPtr sub_control_; + rclcpp::Publisher::SharedPtr pub_ackermann_control_command_; +}; +} // namespace autoware_auto_msgs_adapter + +#endif // AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ diff --git a/simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml b/simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml new file mode 100755 index 0000000000000..9763bc2e226da --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/simulator/autoware_auto_msgs_adapter/package.xml b/simulator/autoware_auto_msgs_adapter/package.xml new file mode 100644 index 0000000000000..54a8136f5f077 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/package.xml @@ -0,0 +1,27 @@ + + + + autoware_auto_msgs_adapter + 1.0.0 + Converts an autoware_msgs message to autoware_auto_msgs version and publishes it. + M. Fatih Cırıt + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + rosidl_default_generators + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + autoware_auto_control_msgs + autoware_control_msgs + rclcpp + rclcpp_components + + + ament_cmake + + diff --git a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp new file mode 100644 index 0000000000000..cb59414135ac5 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -0,0 +1,45 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp" + +#include + +namespace autoware_auto_msgs_adapter +{ + +using autoware_auto_control_msgs::msg::AckermannControlCommand; +using autoware_control_msgs::msg::Control; + +AutowareAutoMsgsAdapterNode::AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptions & node_options) +: rclcpp::Node("autoware_auto_msgs_adapter", node_options) +{ + using Adapter = rclcpp::TypeAdapter; + + pub_ackermann_control_command_ = + create_publisher("ackermann_control_command", rclcpp::QoS{1}); + + sub_control_ = create_subscription( + "control_command", rclcpp::QoS{1}, [this](const Control::SharedPtr msg) { + AckermannControlCommand ackermann_control_command; + rclcpp::TypeAdapter::convert_to_ros_message( + *msg, ackermann_control_command); + pub_ackermann_control_command_->publish(ackermann_control_command); + }); +} + +} // namespace autoware_auto_msgs_adapter + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode) diff --git a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp new file mode 100644 index 0000000000000..ac067d0905274 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp @@ -0,0 +1,21 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +TEST(Test1, Test1_1) // NOLINT for gtest +{ + auto a = 1; + EXPECT_EQ(a, 1); +} \ No newline at end of file diff --git a/simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp b/simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp new file mode 100644 index 0000000000000..1cb10f4d608be --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp @@ -0,0 +1,25 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +int main(int argc, char * argv[]) +{ + testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + bool result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; +} From b4a2ddbf288ae13d0def4197ad4f4f9df1336436 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 5 Jun 2023 18:44:22 +0300 Subject: [PATCH 02/28] test wip MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_auto_msgs_adapter/CMakeLists.txt | 4 +-- .../test/test_1.cpp | 29 +++++++++++++++++-- 2 files changed, 28 insertions(+), 5 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/CMakeLists.txt b/simulator/autoware_auto_msgs_adapter/CMakeLists.txt index 2b95f80f8681f..9879d0b9d50c1 100644 --- a/simulator/autoware_auto_msgs_adapter/CMakeLists.txt +++ b/simulator/autoware_auto_msgs_adapter/CMakeLists.txt @@ -17,8 +17,8 @@ rclcpp_components_register_node(${NODE_NAME} EXECUTABLE ${EXEC_NAME}) if(BUILD_TESTING) - file(GLOB_RECURSE FILES_TEST test/*.cpp) - ament_add_ros_isolated_gtest(${TEST_NAME} ${FILES_TEST}) + file(GLOB_RECURSE TEST_SOURCES test/*.cpp) + ament_add_ros_isolated_gtest(${TEST_NAME} ${TEST_SOURCES}) target_link_libraries(${TEST_NAME} ${NODE_NAME}) endif() diff --git a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp index ac067d0905274..8cb51b27c552b 100644 --- a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp +++ b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp @@ -12,10 +12,33 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include + #include -TEST(Test1, Test1_1) // NOLINT for gtest +class AutowareAutoMsgsAdapterFixture : public testing::Test +{ +protected: + using AutowareAutoMsgsAdapterNode = autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode; + + void SetUp() override + { + rclcpp::init(0, nullptr); + rclcpp::NodeOptions node_options; + node_ = std::make_shared(node_options); + } + + void TearDown() override { rclcpp::shutdown(); } + + autoware_auto_control_msgs::msg::AckermannControlCommand ackermann_control_command_; + + AutowareAutoMsgsAdapterNode::SharedPtr node_; +}; + +TEST_F(AutowareAutoMsgsAdapterFixture, Test1_1) // NOLINT for gtest { - auto a = 1; - EXPECT_EQ(a, 1); + auto dummy_node = std::make_shared("dummy_node", rclcpp::NodeOptions{}); + auto pub = dummy_node->create_publisher( + "ackermann_control_command", rclcpp::QoS{1}); + pub->publish(ackermann_control_command_); } \ No newline at end of file From 97ad36b32496a1178af3aa0523aa34420753a365 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 5 Jun 2023 18:47:15 +0300 Subject: [PATCH 03/28] context is already init MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- simulator/autoware_auto_msgs_adapter/test/test_1.cpp | 3 +-- .../test/test_autoware_auto_msgs_adapter.cpp | 1 + 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp index 8cb51b27c552b..96cf591ab8ff6 100644 --- a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp +++ b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp @@ -23,7 +23,6 @@ class AutowareAutoMsgsAdapterFixture : public testing::Test void SetUp() override { - rclcpp::init(0, nullptr); rclcpp::NodeOptions node_options; node_ = std::make_shared(node_options); } @@ -41,4 +40,4 @@ TEST_F(AutowareAutoMsgsAdapterFixture, Test1_1) // NOLINT for gtest auto pub = dummy_node->create_publisher( "ackermann_control_command", rclcpp::QoS{1}); pub->publish(ackermann_control_command_); -} \ No newline at end of file +} diff --git a/simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp b/simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp index 1cb10f4d608be..6b19ae6e30555 100644 --- a/simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp +++ b/simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include + #include int main(int argc, char * argv[]) From 14ab27b839448fb35f6d843bface1f732b3b34e9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 12 Jun 2023 20:12:31 +0300 Subject: [PATCH 04/28] make it modular MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_auto_msgs_adapter/CMakeLists.txt | 3 + .../autoware_auto_msgs_adapter.param.yaml | 4 +- .../adapter_base.hpp | 58 ++++++++++++++++ .../adapter_base_interface.hpp | 33 +++++++++ .../adapter_control.hpp | 69 +++++++++++++++++++ .../autoware_auto_msgs_adapter_core.hpp | 61 ++-------------- .../src/autoware_auto_msgs_adapter_core.cpp | 25 +++---- .../test/test_1.cpp | 1 + 8 files changed, 184 insertions(+), 70 deletions(-) create mode 100644 simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp create mode 100644 simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp create mode 100644 simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp diff --git a/simulator/autoware_auto_msgs_adapter/CMakeLists.txt b/simulator/autoware_auto_msgs_adapter/CMakeLists.txt index 9879d0b9d50c1..745b0462f060d 100644 --- a/simulator/autoware_auto_msgs_adapter/CMakeLists.txt +++ b/simulator/autoware_auto_msgs_adapter/CMakeLists.txt @@ -10,6 +10,9 @@ set(TEST_NAME test_${PROJECT_NAME}) ament_auto_add_library(${NODE_NAME} SHARED src/autoware_auto_msgs_adapter_core.cpp + include/autoware_auto_msgs_adapter/adapter_base_interface.hpp + include/autoware_auto_msgs_adapter/adapter_base.hpp + include/autoware_auto_msgs_adapter/adapter_control.hpp include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp) rclcpp_components_register_node(${NODE_NAME} diff --git a/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml b/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml index 3f753f5ce0019..dad359252b8a7 100644 --- a/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml +++ b/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml @@ -1,3 +1,5 @@ /**: ros__parameters: - test: 123 + msg_type_target: "autoware_auto_control_msgs::msg::AckermannControlCommand" + topic_name_source: "topic_name_source" + topic_name_target: "topic_name_target" diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp new file mode 100644 index 0000000000000..2e5c406811995 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp @@ -0,0 +1,58 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef BUILD_ADAPTER_BASE_HPP +#define BUILD_ADAPTER_BASE_HPP + +#include "autoware_auto_msgs_adapter/adapter_base_interface.hpp" + +#include + +#include +#include + +namespace autoware_auto_msgs_adapter +{ + +template +class AdapterBase : public AdapterBaseInterface +{ +public: + using SharedPtr = std::shared_ptr>; + using ConstSharedPtr = const SharedPtr; + + explicit AdapterBase( + rclcpp::Node & node, const std::string & topic_name_source, + const std::string & topic_name_target, const rclcpp::QoS & qos = rclcpp::QoS{1}) + { + pub_target_ = node.create_publisher(topic_name_target, qos); + sub_source_ = node.create_subscription( + topic_name_source, qos, std::bind(&AdapterBase::callback, this, std::placeholders::_1)); + } + virtual ~AdapterBase() = default; + + typename rclcpp::Subscription::SharedPtr sub_source_; + typename rclcpp::Publisher::SharedPtr pub_target_; + +protected: + virtual TargetT convert(const SourceT & msg_source) = 0; + + void callback(const typename SourceT::SharedPtr msg_source) + { + pub_target_->publish(convert(*msg_source)); + } +}; + +} // namespace autoware_auto_msgs_adapter + +#endif // BUILD_ADAPTER_BASE_HPP diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp new file mode 100644 index 0000000000000..c2ffc58009945 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp @@ -0,0 +1,33 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef BUILD_ADAPTER_BASE_INTERFACE_HPP +#define BUILD_ADAPTER_BASE_INTERFACE_HPP + +#include + +#include + +namespace autoware_auto_msgs_adapter +{ + +class AdapterBaseInterface +{ +public: + using SharedPtrInterface = std::shared_ptr; + using ConstSharedPtrInterface = const SharedPtrInterface; +}; + +} // namespace autoware_auto_msgs_adapter + +#endif // BUILD_ADAPTER_BASE_INTERFACE_HPP diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp new file mode 100644 index 0000000000000..9d86c579699f4 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp @@ -0,0 +1,69 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ + +#include "autoware_auto_msgs_adapter/adapter_base.hpp" + +#include + +#include +#include + +namespace autoware_auto_msgs_adapter +{ +using autoware_auto_control_msgs::msg::AckermannControlCommand; +using autoware_control_msgs::msg::Control; + +class AdapterControl +: public autoware_auto_msgs_adapter::AdapterBase +{ +public: +protected: +public: + explicit AdapterControl( + rclcpp::Node & node, const std::string & topic_name_source, + const std::string & topic_name_target, const rclcpp::QoS & qos = rclcpp::QoS{1}) + : AdapterBase(node, topic_name_source, topic_name_target, qos) + { + RCLCPP_DEBUG( + node.get_logger(), "AdapterControl is initialized to convert: %s -> %s", + topic_name_source.c_str(), topic_name_target.c_str()); + } + +protected: + AckermannControlCommand convert(const Control & msg_source) override + { + autoware_auto_control_msgs::msg::AckermannControlCommand msg_auto; + msg_auto.stamp = msg_source.stamp; + + const auto & lateral = msg_source.lateral; + auto & lateral_auto = msg_auto.lateral; + lateral_auto.stamp = lateral.stamp; + lateral_auto.steering_tire_angle = lateral.steering_tire_angle; + lateral_auto.steering_tire_rotation_rate = lateral.steering_tire_rotation_rate; + + const auto & longitudinal = msg_source.longitudinal; + auto & longitudinal_auto = msg_auto.longitudinal; + longitudinal_auto.stamp = longitudinal.stamp; + longitudinal_auto.acceleration = longitudinal.acceleration; + longitudinal_auto.jerk = longitudinal.jerk; + longitudinal_auto.speed = longitudinal.velocity; + + return msg_auto; + } +}; +} // namespace autoware_auto_msgs_adapter + +#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp index 8edf7564bd0a3..1be95081eabb3 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp @@ -14,75 +14,22 @@ #ifndef AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ #define AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ -#include -#include - -#include -#include - -/// custom_type: autoware_control_msgs::msg::Control -/// ros_message_type: autoware_auto_control_msgs::msg::AckermannControlCommand -template <> -struct rclcpp::TypeAdapter< - autoware_control_msgs::msg::Control, autoware_auto_control_msgs::msg::AckermannControlCommand> -{ - using is_specialized = std::true_type; - using custom_type = autoware_control_msgs::msg::Control; - using ros_message_type = autoware_auto_control_msgs::msg::AckermannControlCommand; - - /// \brief Convert from custom type to ROS message type. Will be used when subscribing to a - /// autoware_auto_control_msgs::msg::AckermannControlCommand topic. - static void convert_to_ros_message(const custom_type & source, ros_message_type & destination) - { - destination.stamp = source.stamp; +#include "autoware_auto_msgs_adapter/adapter_control.hpp" - const auto & lateral_auto = source.lateral; - auto & lateral = destination.lateral; - lateral.stamp = lateral_auto.stamp; - lateral.steering_tire_angle = lateral_auto.steering_tire_angle; - lateral.steering_tire_rotation_rate = lateral_auto.steering_tire_rotation_rate; - - const auto & longitudinal_auto = source.longitudinal; - auto & longitudinal = destination.longitudinal; - longitudinal.stamp = longitudinal_auto.stamp; - longitudinal.acceleration = longitudinal_auto.acceleration; - longitudinal.jerk = longitudinal_auto.jerk; - longitudinal.speed = longitudinal_auto.velocity; - } - - static void convert_to_custom(const ros_message_type & source, custom_type & destination) - { - destination.stamp = source.stamp; - - const auto & lateral = source.lateral; - auto & lateral_auto = destination.lateral; - lateral_auto.stamp = lateral.stamp; - lateral_auto.steering_tire_angle = lateral.steering_tire_angle; - lateral_auto.steering_tire_rotation_rate = lateral.steering_tire_rotation_rate; +#include - const auto & longitudinal = source.longitudinal; - auto & longitudinal_auto = destination.longitudinal; - longitudinal_auto.stamp = longitudinal.stamp; - longitudinal_auto.acceleration = longitudinal.acceleration; - longitudinal_auto.jerk = longitudinal.jerk; - longitudinal_auto.velocity = longitudinal.speed; - } -}; +#include namespace autoware_auto_msgs_adapter { -using autoware_auto_control_msgs::msg::AckermannControlCommand; -using autoware_control_msgs::msg::Control; -using Adapter = rclcpp::TypeAdapter; class AutowareAutoMsgsAdapterNode : public rclcpp::Node { public: explicit AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptions & node_options); private: - rclcpp::Subscription::SharedPtr sub_control_; - rclcpp::Publisher::SharedPtr pub_ackermann_control_command_; + AdapterBaseInterface::SharedPtrInterface adapter_; }; } // namespace autoware_auto_msgs_adapter diff --git a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index cb59414135ac5..45278e135e30e 100644 --- a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -14,6 +14,8 @@ #include "autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp" +#include "autoware_auto_msgs_adapter/adapter_control.hpp" + #include namespace autoware_auto_msgs_adapter @@ -25,18 +27,17 @@ using autoware_control_msgs::msg::Control; AutowareAutoMsgsAdapterNode::AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptions & node_options) : rclcpp::Node("autoware_auto_msgs_adapter", node_options) { - using Adapter = rclcpp::TypeAdapter; - - pub_ackermann_control_command_ = - create_publisher("ackermann_control_command", rclcpp::QoS{1}); - - sub_control_ = create_subscription( - "control_command", rclcpp::QoS{1}, [this](const Control::SharedPtr msg) { - AckermannControlCommand ackermann_control_command; - rclcpp::TypeAdapter::convert_to_ros_message( - *msg, ackermann_control_command); - pub_ackermann_control_command_->publish(ackermann_control_command); - }); + std::string msg_type_target = declare_parameter("msg_type_target"); + std::string topic_name_source = declare_parameter("topic_name_source"); + std::string topic_name_target = declare_parameter("topic_name_target"); + + if (msg_type_target == "autoware_auto_control_msgs::msg::AckermannControlCommand") { + AdapterControl::SharedPtr adapter = + std::make_shared(*this, topic_name_source, topic_name_target); + adapter_ = std::dynamic_pointer_cast(adapter); + } else { + RCLCPP_ERROR(get_logger(), "Unknown msg type: %s", msg_type_target.c_str()); + } } } // namespace autoware_auto_msgs_adapter diff --git a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp index 96cf591ab8ff6..179858bf066dc 100644 --- a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp +++ b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp @@ -40,4 +40,5 @@ TEST_F(AutowareAutoMsgsAdapterFixture, Test1_1) // NOLINT for gtest auto pub = dummy_node->create_publisher( "ackermann_control_command", rclcpp::QoS{1}); pub->publish(ackermann_control_command_); + } From cac08e459150fd61a54d626b338059b692f6acf6 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 12 Jun 2023 17:14:12 +0000 Subject: [PATCH 05/28] style(pre-commit): autofix --- .../include/autoware_auto_msgs_adapter/adapter_base.hpp | 6 +++--- .../autoware_auto_msgs_adapter/adapter_base_interface.hpp | 6 +++--- simulator/autoware_auto_msgs_adapter/test/test_1.cpp | 1 - 3 files changed, 6 insertions(+), 7 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp index 2e5c406811995..39fd01786908e 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp @@ -11,8 +11,8 @@ // 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 BUILD_ADAPTER_BASE_HPP -#define BUILD_ADAPTER_BASE_HPP +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ #include "autoware_auto_msgs_adapter/adapter_base_interface.hpp" @@ -55,4 +55,4 @@ class AdapterBase : public AdapterBaseInterface } // namespace autoware_auto_msgs_adapter -#endif // BUILD_ADAPTER_BASE_HPP +#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp index c2ffc58009945..bf37101aedca6 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp @@ -11,8 +11,8 @@ // 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 BUILD_ADAPTER_BASE_INTERFACE_HPP -#define BUILD_ADAPTER_BASE_INTERFACE_HPP +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ #include @@ -30,4 +30,4 @@ class AdapterBaseInterface } // namespace autoware_auto_msgs_adapter -#endif // BUILD_ADAPTER_BASE_INTERFACE_HPP +#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ diff --git a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp index 179858bf066dc..96cf591ab8ff6 100644 --- a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp +++ b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp @@ -40,5 +40,4 @@ TEST_F(AutowareAutoMsgsAdapterFixture, Test1_1) // NOLINT for gtest auto pub = dummy_node->create_publisher( "ackermann_control_command", rclcpp::QoS{1}); pub->publish(ackermann_control_command_); - } From 1bcb59b3e2a95c12c8cee7f6a9d4284a29e632da Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 12 Jun 2023 21:05:47 +0300 Subject: [PATCH 06/28] create the test for ackerman control command MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../test/test_1.cpp | 43 ------- .../test_msg_ackerman_control_command.cpp | 116 ++++++++++++++++++ 2 files changed, 116 insertions(+), 43 deletions(-) delete mode 100644 simulator/autoware_auto_msgs_adapter/test/test_1.cpp create mode 100644 simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp diff --git a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp b/simulator/autoware_auto_msgs_adapter/test/test_1.cpp deleted file mode 100644 index 96cf591ab8ff6..0000000000000 --- a/simulator/autoware_auto_msgs_adapter/test/test_1.cpp +++ /dev/null @@ -1,43 +0,0 @@ -// Copyright 2023 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -#include - -class AutowareAutoMsgsAdapterFixture : public testing::Test -{ -protected: - using AutowareAutoMsgsAdapterNode = autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode; - - void SetUp() override - { - rclcpp::NodeOptions node_options; - node_ = std::make_shared(node_options); - } - - void TearDown() override { rclcpp::shutdown(); } - - autoware_auto_control_msgs::msg::AckermannControlCommand ackermann_control_command_; - - AutowareAutoMsgsAdapterNode::SharedPtr node_; -}; - -TEST_F(AutowareAutoMsgsAdapterFixture, Test1_1) // NOLINT for gtest -{ - auto dummy_node = std::make_shared("dummy_node", rclcpp::NodeOptions{}); - auto pub = dummy_node->create_publisher( - "ackermann_control_command", rclcpp::QoS{1}); - pub->publish(ackermann_control_command_); -} diff --git a/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp b/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp new file mode 100644 index 0000000000000..04c6f7abf3d4b --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp @@ -0,0 +1,116 @@ +// Copyright 2023 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +#include + +autoware_control_msgs::msg::Control generate_control_msg() +{ + // generate deterministic random float + std::mt19937 gen(0); + std::uniform_real_distribution<> dis(-100.0, 100.0); + auto rand_float = [&dis, &gen]() { return static_cast(dis(gen)); }; + + // generate deterministic random int + std::uniform_int_distribution<> dis_int(0, 1000000); + auto rand_int = [&dis_int, &gen]() { return dis_int(gen); }; + + autoware_control_msgs::msg::Control msg_control; + msg_control.stamp = rclcpp::Time(rand_int()); + + msg_control.lateral.stamp = rclcpp::Time(rand_int()); + msg_control.lateral.steering_tire_angle = rand_float(); + msg_control.lateral.steering_tire_rotation_rate = rand_float(); + + msg_control.longitudinal.stamp = rclcpp::Time(rand_int()); + msg_control.longitudinal.velocity = rand_float(); + msg_control.longitudinal.jerk = rand_float(); + msg_control.longitudinal.acceleration = rand_float(); + return msg_control; +} + +TEST(AutowareAutoMsgsAdapter, TestMsgAckermannControlCommand) // NOLINT for gtest +{ + const std::string msg_type_target = "autoware_auto_control_msgs::msg::AckermannControlCommand"; + const std::string topic_name_source = "topic_name_source"; + const std::string topic_name_target = "topic_name_target"; + + std::cout << "Creating the adapter node..." << std::endl; + + rclcpp::NodeOptions node_options; + node_options.append_parameter_override("msg_type_target", msg_type_target); + node_options.append_parameter_override("topic_name_source", topic_name_source); + node_options.append_parameter_override("topic_name_target", topic_name_target); + + using autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode; + AutowareAutoMsgsAdapterNode::SharedPtr node_adapter; + node_adapter = std::make_shared(node_options); + + std::cout << "Creating the subscriber node..." << std::endl; + + auto node_subscriber = std::make_shared("node_subscriber", rclcpp::NodeOptions{}); + + bool test_completed = false; + + const auto msg_control = generate_control_msg(); + auto sub = + node_subscriber->create_subscription( + topic_name_target, rclcpp::QoS{1}, + [&msg_control, &test_completed]( + const autoware_auto_control_msgs::msg::AckermannControlCommand::SharedPtr msg) { + EXPECT_EQ(msg->stamp, msg_control.stamp); + + EXPECT_EQ(msg->lateral.stamp, msg_control.lateral.stamp); + EXPECT_FLOAT_EQ(msg->lateral.steering_tire_angle, msg_control.lateral.steering_tire_angle); + EXPECT_FLOAT_EQ( + msg->lateral.steering_tire_rotation_rate, + msg_control.lateral.steering_tire_rotation_rate); + + EXPECT_EQ(msg->longitudinal.stamp, msg_control.longitudinal.stamp); + EXPECT_FLOAT_EQ(msg->longitudinal.speed, msg_control.longitudinal.velocity); + EXPECT_FLOAT_EQ(msg->longitudinal.acceleration, msg_control.longitudinal.acceleration); + EXPECT_FLOAT_EQ(msg->longitudinal.jerk, msg_control.longitudinal.jerk); + test_completed = true; + }); + + std::cout << "Creating the publisher node..." << std::endl; + + auto node_publisher = std::make_shared("node_publisher", rclcpp::NodeOptions{}); + auto pub = node_publisher->create_publisher( + topic_name_source, rclcpp::QoS{1}); + pub->publish(msg_control); + + auto start_time = std::chrono::system_clock::now(); + auto max_test_dur = std::chrono::seconds(5); + auto timed_out = false; + + while (rclcpp::ok() && !test_completed) { + rclcpp::spin_some(node_subscriber); + rclcpp::spin_some(node_adapter); + rclcpp::spin_some(node_publisher); + rclcpp::sleep_for(std::chrono::milliseconds(50)); + if (std::chrono::system_clock::now() - start_time > max_test_dur) { + timed_out = true; + break; + } + } + + EXPECT_TRUE(test_completed); + EXPECT_FALSE(timed_out); + + rclcpp::shutdown(); +} From 052dfe578d4a42e00308ef4ff0c17ad501bfa34c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 12 Jun 2023 21:13:06 +0300 Subject: [PATCH 07/28] add missing header MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../include/autoware_auto_msgs_adapter/adapter_control.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp index 9d86c579699f4..0e18ceb14932e 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp @@ -21,6 +21,8 @@ #include #include +#include + namespace autoware_auto_msgs_adapter { using autoware_auto_control_msgs::msg::AckermannControlCommand; From 5db44abec9463049dcd94003365168fcf29a5858 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 13 Jun 2023 17:04:32 +0300 Subject: [PATCH 08/28] use RCLCPP_SHARED_PTR_DEFINITIONS MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../include/autoware_auto_msgs_adapter/adapter_base.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp index 39fd01786908e..a523c13d74477 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp @@ -28,8 +28,7 @@ template class AdapterBase : public AdapterBaseInterface { public: - using SharedPtr = std::shared_ptr>; - using ConstSharedPtr = const SharedPtr; + RCLCPP_SHARED_PTR_DEFINITIONS(AdapterBase) explicit AdapterBase( rclcpp::Node & node, const std::string & topic_name_source, From 19b518835018c3f1a8d8cec75526a32ed354af4f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 13 Jun 2023 17:13:17 +0300 Subject: [PATCH 09/28] move the virtual destructor to the base class MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../include/autoware_auto_msgs_adapter/adapter_base.hpp | 1 - .../autoware_auto_msgs_adapter/adapter_base_interface.hpp | 2 ++ 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp index a523c13d74477..2052896c5d11a 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp @@ -38,7 +38,6 @@ class AdapterBase : public AdapterBaseInterface sub_source_ = node.create_subscription( topic_name_source, qos, std::bind(&AdapterBase::callback, this, std::placeholders::_1)); } - virtual ~AdapterBase() = default; typename rclcpp::Subscription::SharedPtr sub_source_; typename rclcpp::Publisher::SharedPtr pub_target_; diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp index bf37101aedca6..d81c7bc590f60 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp @@ -26,6 +26,8 @@ class AdapterBaseInterface public: using SharedPtrInterface = std::shared_ptr; using ConstSharedPtrInterface = const SharedPtrInterface; + + virtual ~AdapterBaseInterface() = default; }; } // namespace autoware_auto_msgs_adapter From 8e2881a863b35aa4f6284b6a2ad502435ef7514a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 13 Jun 2023 17:16:01 +0300 Subject: [PATCH 10/28] make members private MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../include/autoware_auto_msgs_adapter/adapter_base.hpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp index 2052896c5d11a..0a94dc61e878e 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp @@ -39,12 +39,13 @@ class AdapterBase : public AdapterBaseInterface topic_name_source, qos, std::bind(&AdapterBase::callback, this, std::placeholders::_1)); } - typename rclcpp::Subscription::SharedPtr sub_source_; - typename rclcpp::Publisher::SharedPtr pub_target_; - protected: virtual TargetT convert(const SourceT & msg_source) = 0; +private: + typename rclcpp::Publisher::SharedPtr pub_target_; + typename rclcpp::Subscription::SharedPtr sub_source_; + void callback(const typename SourceT::SharedPtr msg_source) { pub_target_->publish(convert(*msg_source)); From 25fa0f10604f6063c4e7bf22413cc5436d714092 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 13 Jun 2023 17:20:38 +0300 Subject: [PATCH 11/28] remove unnecessary explicit MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt remove unnecessary explicit Signed-off-by: M. Fatih Cırıt --- .../include/autoware_auto_msgs_adapter/adapter_base.hpp | 2 +- .../include/autoware_auto_msgs_adapter/adapter_control.hpp | 4 +--- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp index 0a94dc61e878e..05104985e39ba 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp @@ -30,7 +30,7 @@ class AdapterBase : public AdapterBaseInterface public: RCLCPP_SHARED_PTR_DEFINITIONS(AdapterBase) - explicit AdapterBase( + AdapterBase( rclcpp::Node & node, const std::string & topic_name_source, const std::string & topic_name_target, const rclcpp::QoS & qos = rclcpp::QoS{1}) { diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp index 0e18ceb14932e..0204747438398 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp @@ -32,9 +32,7 @@ class AdapterControl : public autoware_auto_msgs_adapter::AdapterBase { public: -protected: -public: - explicit AdapterControl( + AdapterControl( rclcpp::Node & node, const std::string & topic_name_source, const std::string & topic_name_target, const rclcpp::QoS & qos = rclcpp::QoS{1}) : AdapterBase(node, topic_name_source, topic_name_target, qos) From a4e98e0f78160a18ec728839593ed5c9c42cc958 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 13 Jun 2023 17:37:50 +0300 Subject: [PATCH 12/28] refactor SharedPtrInterface to just SharedPtr for the base interface class MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_auto_msgs_adapter/adapter_base_interface.hpp | 3 +-- .../autoware_auto_msgs_adapter_core.hpp | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp index d81c7bc590f60..e22b81e28f661 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp @@ -24,8 +24,7 @@ namespace autoware_auto_msgs_adapter class AdapterBaseInterface { public: - using SharedPtrInterface = std::shared_ptr; - using ConstSharedPtrInterface = const SharedPtrInterface; + RCLCPP_SHARED_PTR_DEFINITIONS(AdapterBaseInterface) virtual ~AdapterBaseInterface() = default; }; diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp index 1be95081eabb3..f05349165541f 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp @@ -29,7 +29,7 @@ class AutowareAutoMsgsAdapterNode : public rclcpp::Node explicit AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptions & node_options); private: - AdapterBaseInterface::SharedPtrInterface adapter_; + AdapterBaseInterface::SharedPtr adapter_; }; } // namespace autoware_auto_msgs_adapter From f90c0b7ff81e4413a5aa4ca6b41d39e85c6d8085 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 13 Jun 2023 17:46:15 +0300 Subject: [PATCH 13/28] use static_pointer_cast MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../src/autoware_auto_msgs_adapter_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index 45278e135e30e..3c91804b2282d 100644 --- a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -34,7 +34,7 @@ AutowareAutoMsgsAdapterNode::AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptio if (msg_type_target == "autoware_auto_control_msgs::msg::AckermannControlCommand") { AdapterControl::SharedPtr adapter = std::make_shared(*this, topic_name_source, topic_name_target); - adapter_ = std::dynamic_pointer_cast(adapter); + adapter_ = std::static_pointer_cast(adapter); } else { RCLCPP_ERROR(get_logger(), "Unknown msg type: %s", msg_type_target.c_str()); } From a3f9ff9b5bdd344f088fa14fc69a0ebb37505eac Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 13 Jun 2023 17:47:31 +0300 Subject: [PATCH 14/28] const vars MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../src/autoware_auto_msgs_adapter_core.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index 3c91804b2282d..c2595b5043099 100644 --- a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -27,9 +27,9 @@ using autoware_control_msgs::msg::Control; AutowareAutoMsgsAdapterNode::AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptions & node_options) : rclcpp::Node("autoware_auto_msgs_adapter", node_options) { - std::string msg_type_target = declare_parameter("msg_type_target"); - std::string topic_name_source = declare_parameter("topic_name_source"); - std::string topic_name_target = declare_parameter("topic_name_target"); + const std::string msg_type_target = declare_parameter("msg_type_target"); + const std::string topic_name_source = declare_parameter("topic_name_source"); + const std::string topic_name_target = declare_parameter("topic_name_target"); if (msg_type_target == "autoware_auto_control_msgs::msg::AckermannControlCommand") { AdapterControl::SharedPtr adapter = From 5c2cc5d81fb66ab94b037a1919e8541834aba3d6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 14 Jun 2023 13:17:13 +0300 Subject: [PATCH 15/28] add readme MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_auto_msgs_adapter/README.md | 94 +++++++++++++++++++ .../config/adapter_control.param.yaml | 5 + .../autoware_auto_msgs_adapter.param.yaml | 5 - .../autoware_auto_msgs_adapter.launch.xml | 2 +- 4 files changed, 100 insertions(+), 6 deletions(-) create mode 100644 simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml delete mode 100644 simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml diff --git a/simulator/autoware_auto_msgs_adapter/README.md b/simulator/autoware_auto_msgs_adapter/README.md index 3e9eed2112275..8668b1c92bedc 100644 --- a/simulator/autoware_auto_msgs_adapter/README.md +++ b/simulator/autoware_auto_msgs_adapter/README.md @@ -1 +1,95 @@ # autoware_auto_msgs_adapter + +This package is used to convert `autoware_msgs` to `autoware_auto_msgs`. + +## Purpose + +As we transition from `autoware_auto_msgs` to `autoware_msgs`, we wanted to provide flexibility and compatibility for +users who are still using `autoware_auto_msgs`. + +This adapter package allows users to easily convert messages between the two formats. + +## Capabilities + +The `autoware_auto_msgs_adapter` package provides the following capabilities: + +- Conversion of supported `autoware_msgs` messages to `autoware_auto_msgs` messages. +- Can be extended to support conversion for any message type pairs. +- Each instance is designed to convert from a single source message type to a single target message type. +- Multiple instances can be launched to convert multiple message types. +- Can be launched as a standalone node or as a component. + +## Usage + +Customize the adapter configuration by replicating and editing the `adapter_control.param.yaml` file located +in the `autoware_auto_msgs_adapter/config` directory. Example configuration: + +```yaml +/**: + ros__parameters: + msg_type_target: "autoware_auto_control_msgs::msg::AckermannControlCommand" + topic_name_source: "/control/command/control_cmd" + topic_name_target: "/control/command/control_cmd_auto" +``` + +Set the `msg_type_target` parameter to the desired target message type from `autoware_auto_msgs`. + +Make sure that the `msg_type_target` has the correspondence +in [src/autoware_auto_msgs_adapter_core.cpp](src/autoware_auto_msgs_adapter_core.cpp). + +Launch the adapter node by any of the following methods: + +### `ros2 launch` + +```bash +ros2 launch autoware_auto_msgs_adapter autoware_auto_msgs_adapter.launch.xml param_path:='full_path_to_param_file' +``` + +Make sure to set the `param_path` argument to the full path of the parameter file. + +Alternatively, + +- You can replicate and edit the launch file to suit to your needs. +- You can make use of the existing launch file in another launch file by providing the parameter file path as an + argument. + +### `ros2 run` + +```bash +ros2 run autoware_auto_msgs_adapter autoware_auto_msgs_adapter_exe --ros-args --params-file 'full_path_to_param_file' +``` + +Make sure to set the `param_path` argument to the full path of the parameter file. + +## Contributing + +### Current implementation details + +The entry point for the adapter executable is created with `RCLCPP_COMPONENTS_REGISTER_NODE` the [autoware_auto_msgs_adapter_core.cpp](src/Fautoware_auto_msgs_adapter_core.cpp). + +This allows it to be launched as a component or as a standalone node. + +In the `AutowareAutoMsgsAdapterNode` constructor, the adapter is selected by the type string provided in the +configuration file. The adapter is then initialized with the topic names provided. + +The constructors of the adapters are responsible for creating the publisher and subscriber (which makes use of the conversion method). + +### Adding a new message pair + +To add a new message pair, +- Replicate and edit: + - [adapter_control.hpp](include/autoware_auto_msgs_adapter/adapter_control.hpp). + - Add the new header file to the [CMakeLists.txt](CMakeLists.txt). +- Add a new entry in the if-else if block in the constructor of the adapter node: + - [autoware_auto_msgs_adapter_core.cpp](src/autoware_auto_msgs_adapter_core.cpp) +- Create a new config file by replicating and editing: + - [adapter_control.param.yaml](config/adapter_control.param.yaml) +- Add a new test file by replicating and editing: + - [test_msg_ackerman_control_command.cpp](test/test_msg_ackerman_control_command.cpp) + - No need to edit the `CMakeLists.txt` file as it will automatically detect the new test file. + +Also make sure to test the new adapter with: + +```bash +colcon test --event-handlers console_cohesion+ --packages-select autoware_auto_msgs_adapter +``` diff --git a/simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml b/simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml new file mode 100644 index 0000000000000..614826f148d46 --- /dev/null +++ b/simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + msg_type_target: "autoware_auto_control_msgs::msg::AckermannControlCommand" + topic_name_source: "/control/command/control_cmd" + topic_name_target: "/control/command/control_cmd_auto" diff --git a/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml b/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml deleted file mode 100644 index dad359252b8a7..0000000000000 --- a/simulator/autoware_auto_msgs_adapter/config/autoware_auto_msgs_adapter.param.yaml +++ /dev/null @@ -1,5 +0,0 @@ -/**: - ros__parameters: - msg_type_target: "autoware_auto_control_msgs::msg::AckermannControlCommand" - topic_name_source: "topic_name_source" - topic_name_target: "topic_name_target" diff --git a/simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml b/simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml index 9763bc2e226da..89b58e2d60c28 100755 --- a/simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml +++ b/simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml @@ -1,6 +1,6 @@ - + From 86b591426dde0b54df771b33bd6032a62a74ebd9 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 14 Jun 2023 10:25:03 +0000 Subject: [PATCH 16/28] style(pre-commit): autofix --- simulator/autoware_auto_msgs_adapter/README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/simulator/autoware_auto_msgs_adapter/README.md b/simulator/autoware_auto_msgs_adapter/README.md index 8668b1c92bedc..fb996ee91aab5 100644 --- a/simulator/autoware_auto_msgs_adapter/README.md +++ b/simulator/autoware_auto_msgs_adapter/README.md @@ -76,7 +76,8 @@ The constructors of the adapters are responsible for creating the publisher and ### Adding a new message pair -To add a new message pair, +To add a new message pair, + - Replicate and edit: - [adapter_control.hpp](include/autoware_auto_msgs_adapter/adapter_control.hpp). - Add the new header file to the [CMakeLists.txt](CMakeLists.txt). From 40ed42e9bb1d1ee8cf13ba072eae4a19f1e77047 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 19 Jun 2023 14:27:52 +0300 Subject: [PATCH 17/28] fix header/library visibility and directories MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- simulator/autoware_auto_msgs_adapter/CMakeLists.txt | 12 ++++++------ .../adapter_base.hpp | 2 +- .../adapter_base_interface.hpp | 0 .../adapter_control.hpp | 2 +- .../autoware_auto_msgs_adapter_core.hpp | 2 +- .../src/autoware_auto_msgs_adapter_core.cpp | 5 ++--- .../test/test_msg_ackerman_control_command.cpp | 2 +- 7 files changed, 12 insertions(+), 13 deletions(-) rename simulator/autoware_auto_msgs_adapter/include/{autoware_auto_msgs_adapter => }/adapter_base.hpp (96%) rename simulator/autoware_auto_msgs_adapter/include/{autoware_auto_msgs_adapter => }/adapter_base_interface.hpp (100%) rename simulator/autoware_auto_msgs_adapter/include/{autoware_auto_msgs_adapter => }/adapter_control.hpp (97%) rename simulator/autoware_auto_msgs_adapter/include/{autoware_auto_msgs_adapter => }/autoware_auto_msgs_adapter_core.hpp (95%) diff --git a/simulator/autoware_auto_msgs_adapter/CMakeLists.txt b/simulator/autoware_auto_msgs_adapter/CMakeLists.txt index 745b0462f060d..194b2257ef8e6 100644 --- a/simulator/autoware_auto_msgs_adapter/CMakeLists.txt +++ b/simulator/autoware_auto_msgs_adapter/CMakeLists.txt @@ -8,12 +8,12 @@ set(NODE_NAME ${PROJECT_NAME}_node) set(EXEC_NAME ${PROJECT_NAME}_exe) set(TEST_NAME test_${PROJECT_NAME}) -ament_auto_add_library(${NODE_NAME} SHARED - src/autoware_auto_msgs_adapter_core.cpp - include/autoware_auto_msgs_adapter/adapter_base_interface.hpp - include/autoware_auto_msgs_adapter/adapter_base.hpp - include/autoware_auto_msgs_adapter/adapter_control.hpp - include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp) +ament_auto_add_library(${NODE_NAME} + src/autoware_auto_msgs_adapter_core.cpp) + +target_include_directories(${NODE_NAME} + PRIVATE + $) rclcpp_components_register_node(${NODE_NAME} PLUGIN "autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode" diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp similarity index 96% rename from simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp rename to simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp index 05104985e39ba..6ba81d169ecec 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ #define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ -#include "autoware_auto_msgs_adapter/adapter_base_interface.hpp" +#include "adapter_base_interface.hpp" #include diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp b/simulator/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp similarity index 100% rename from simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp rename to simulator/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp b/simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp similarity index 97% rename from simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp rename to simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp index 0204747438398..96ff0e297eeef 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ #define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ -#include "autoware_auto_msgs_adapter/adapter_base.hpp" +#include "adapter_base.hpp" #include diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp similarity index 95% rename from simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp rename to simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp index f05349165541f..800858bb9caf8 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ #define AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ -#include "autoware_auto_msgs_adapter/adapter_control.hpp" +#include "adapter_control.hpp" #include diff --git a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index c2595b5043099..b5b015bdd632f 100644 --- a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -12,9 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp" - -#include "autoware_auto_msgs_adapter/adapter_control.hpp" +#include "autoware_auto_msgs_adapter_core.hpp" +#include "adapter_control.hpp" #include diff --git a/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp b/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp index 04c6f7abf3d4b..e824e3a39d97c 100644 --- a/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp +++ b/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include From 14fa392fdf41845f35169b87e46eb573462c5746 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 19 Jun 2023 11:29:24 +0000 Subject: [PATCH 18/28] style(pre-commit): autofix --- .../autoware_auto_msgs_adapter/include/adapter_base.hpp | 6 +++--- .../include/adapter_base_interface.hpp | 6 +++--- .../autoware_auto_msgs_adapter/include/adapter_control.hpp | 6 +++--- .../include/autoware_auto_msgs_adapter_core.hpp | 6 +++--- .../src/autoware_auto_msgs_adapter_core.cpp | 1 + 5 files changed, 13 insertions(+), 12 deletions(-) diff --git a/simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp b/simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp index 6ba81d169ecec..f506d66b1d8b0 100644 --- a/simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ +#ifndef ADAPTER_BASE_HPP_ +#define ADAPTER_BASE_HPP_ #include "adapter_base_interface.hpp" @@ -54,4 +54,4 @@ class AdapterBase : public AdapterBaseInterface } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ +#endif // ADAPTER_BASE_HPP_ diff --git a/simulator/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp b/simulator/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp index e22b81e28f661..606993332fc4a 100644 --- a/simulator/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ +#ifndef ADAPTER_BASE_INTERFACE_HPP_ +#define ADAPTER_BASE_INTERFACE_HPP_ #include @@ -31,4 +31,4 @@ class AdapterBaseInterface } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ +#endif // ADAPTER_BASE_INTERFACE_HPP_ diff --git a/simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp b/simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp index 96ff0e297eeef..c02f4e03877a2 100644 --- a/simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ +#ifndef ADAPTER_CONTROL_HPP_ +#define ADAPTER_CONTROL_HPP_ #include "adapter_base.hpp" @@ -66,4 +66,4 @@ class AdapterControl }; } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ +#endif // ADAPTER_CONTROL_HPP_ diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp index 800858bb9caf8..debe969d6a0bb 100644 --- a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp +++ b/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ #include "adapter_control.hpp" @@ -33,4 +33,4 @@ class AutowareAutoMsgsAdapterNode : public rclcpp::Node }; } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#endif // AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ diff --git a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index b5b015bdd632f..e4b0f94455a52 100644 --- a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include "autoware_auto_msgs_adapter_core.hpp" + #include "adapter_control.hpp" #include From 66edca24d3028a10fe4eae95008f80538f14d0f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 19 Jun 2023 14:36:11 +0300 Subject: [PATCH 19/28] use slash instead, fix test name MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt Signed-off-by: M. Fatih Cırıt --- simulator/autoware_auto_msgs_adapter/README.md | 4 ++-- .../config/adapter_control.param.yaml | 2 +- .../src/autoware_auto_msgs_adapter_core.cpp | 2 +- ...rol_command.cpp => test_msg_ackermann_control_command.cpp} | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) rename simulator/autoware_auto_msgs_adapter/test/{test_msg_ackerman_control_command.cpp => test_msg_ackermann_control_command.cpp} (99%) diff --git a/simulator/autoware_auto_msgs_adapter/README.md b/simulator/autoware_auto_msgs_adapter/README.md index fb996ee91aab5..26fadf6cd0b93 100644 --- a/simulator/autoware_auto_msgs_adapter/README.md +++ b/simulator/autoware_auto_msgs_adapter/README.md @@ -27,7 +27,7 @@ in the `autoware_auto_msgs_adapter/config` directory. Example configuration: ```yaml /**: ros__parameters: - msg_type_target: "autoware_auto_control_msgs::msg::AckermannControlCommand" + msg_type_target: "autoware_auto_control_msgs/msg/AckermannControlCommand" topic_name_source: "/control/command/control_cmd" topic_name_target: "/control/command/control_cmd_auto" ``` @@ -86,7 +86,7 @@ To add a new message pair, - Create a new config file by replicating and editing: - [adapter_control.param.yaml](config/adapter_control.param.yaml) - Add a new test file by replicating and editing: - - [test_msg_ackerman_control_command.cpp](test/test_msg_ackerman_control_command.cpp) + - [test_msg_ackermann_control_command.cpp](test/test_msg_ackermann_control_command.cpp) - No need to edit the `CMakeLists.txt` file as it will automatically detect the new test file. Also make sure to test the new adapter with: diff --git a/simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml b/simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml index 614826f148d46..4c6d5f101f380 100644 --- a/simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml +++ b/simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml @@ -1,5 +1,5 @@ /**: ros__parameters: - msg_type_target: "autoware_auto_control_msgs::msg::AckermannControlCommand" + msg_type_target: "autoware_auto_control_msgs/msg/AckermannControlCommand" topic_name_source: "/control/command/control_cmd" topic_name_target: "/control/command/control_cmd_auto" diff --git a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index e4b0f94455a52..70a48965e8715 100644 --- a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -31,7 +31,7 @@ AutowareAutoMsgsAdapterNode::AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptio const std::string topic_name_source = declare_parameter("topic_name_source"); const std::string topic_name_target = declare_parameter("topic_name_target"); - if (msg_type_target == "autoware_auto_control_msgs::msg::AckermannControlCommand") { + if (msg_type_target == "autoware_auto_control_msgs/msg/AckermannControlCommand") { AdapterControl::SharedPtr adapter = std::make_shared(*this, topic_name_source, topic_name_target); adapter_ = std::static_pointer_cast(adapter); diff --git a/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp b/simulator/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp similarity index 99% rename from simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp rename to simulator/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp index e824e3a39d97c..e33ae07e6aca1 100644 --- a/simulator/autoware_auto_msgs_adapter/test/test_msg_ackerman_control_command.cpp +++ b/simulator/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp @@ -45,7 +45,7 @@ autoware_control_msgs::msg::Control generate_control_msg() TEST(AutowareAutoMsgsAdapter, TestMsgAckermannControlCommand) // NOLINT for gtest { - const std::string msg_type_target = "autoware_auto_control_msgs::msg::AckermannControlCommand"; + const std::string msg_type_target = "autoware_auto_control_msgs/msg/AckermannControlCommand"; const std::string topic_name_source = "topic_name_source"; const std::string topic_name_target = "topic_name_target"; From 4ba25b3745c914848a970a7eaa584facf1a0a82e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 19 Jun 2023 14:38:56 +0300 Subject: [PATCH 20/28] move to system directory MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- {simulator => system}/autoware_auto_msgs_adapter/CMakeLists.txt | 0 {simulator => system}/autoware_auto_msgs_adapter/README.md | 0 .../autoware_auto_msgs_adapter/config/adapter_control.param.yaml | 0 .../autoware_auto_msgs_adapter/include/adapter_base.hpp | 0 .../autoware_auto_msgs_adapter/include/adapter_base_interface.hpp | 0 .../autoware_auto_msgs_adapter/include/adapter_control.hpp | 0 .../include/autoware_auto_msgs_adapter_core.hpp | 0 .../launch/autoware_auto_msgs_adapter.launch.xml | 0 {simulator => system}/autoware_auto_msgs_adapter/package.xml | 0 .../src/autoware_auto_msgs_adapter_core.cpp | 0 .../test/test_autoware_auto_msgs_adapter.cpp | 0 .../test/test_msg_ackermann_control_command.cpp | 0 12 files changed, 0 insertions(+), 0 deletions(-) rename {simulator => system}/autoware_auto_msgs_adapter/CMakeLists.txt (100%) rename {simulator => system}/autoware_auto_msgs_adapter/README.md (100%) rename {simulator => system}/autoware_auto_msgs_adapter/config/adapter_control.param.yaml (100%) rename {simulator => system}/autoware_auto_msgs_adapter/include/adapter_base.hpp (100%) rename {simulator => system}/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp (100%) rename {simulator => system}/autoware_auto_msgs_adapter/include/adapter_control.hpp (100%) rename {simulator => system}/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp (100%) rename {simulator => system}/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml (100%) rename {simulator => system}/autoware_auto_msgs_adapter/package.xml (100%) rename {simulator => system}/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp (100%) rename {simulator => system}/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp (100%) rename {simulator => system}/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp (100%) diff --git a/simulator/autoware_auto_msgs_adapter/CMakeLists.txt b/system/autoware_auto_msgs_adapter/CMakeLists.txt similarity index 100% rename from simulator/autoware_auto_msgs_adapter/CMakeLists.txt rename to system/autoware_auto_msgs_adapter/CMakeLists.txt diff --git a/simulator/autoware_auto_msgs_adapter/README.md b/system/autoware_auto_msgs_adapter/README.md similarity index 100% rename from simulator/autoware_auto_msgs_adapter/README.md rename to system/autoware_auto_msgs_adapter/README.md diff --git a/simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml b/system/autoware_auto_msgs_adapter/config/adapter_control.param.yaml similarity index 100% rename from simulator/autoware_auto_msgs_adapter/config/adapter_control.param.yaml rename to system/autoware_auto_msgs_adapter/config/adapter_control.param.yaml diff --git a/simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp b/system/autoware_auto_msgs_adapter/include/adapter_base.hpp similarity index 100% rename from simulator/autoware_auto_msgs_adapter/include/adapter_base.hpp rename to system/autoware_auto_msgs_adapter/include/adapter_base.hpp diff --git a/simulator/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp b/system/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp similarity index 100% rename from simulator/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp rename to system/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp diff --git a/simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp b/system/autoware_auto_msgs_adapter/include/adapter_control.hpp similarity index 100% rename from simulator/autoware_auto_msgs_adapter/include/adapter_control.hpp rename to system/autoware_auto_msgs_adapter/include/adapter_control.hpp diff --git a/simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp similarity index 100% rename from simulator/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp rename to system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp diff --git a/simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml b/system/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml similarity index 100% rename from simulator/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml rename to system/autoware_auto_msgs_adapter/launch/autoware_auto_msgs_adapter.launch.xml diff --git a/simulator/autoware_auto_msgs_adapter/package.xml b/system/autoware_auto_msgs_adapter/package.xml similarity index 100% rename from simulator/autoware_auto_msgs_adapter/package.xml rename to system/autoware_auto_msgs_adapter/package.xml diff --git a/simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp similarity index 100% rename from simulator/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp rename to system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp diff --git a/simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp b/system/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp similarity index 100% rename from simulator/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp rename to system/autoware_auto_msgs_adapter/test/test_autoware_auto_msgs_adapter.cpp diff --git a/simulator/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp b/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp similarity index 100% rename from simulator/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp rename to system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp From 38a4085f932ee7754f9fa9dc803bec18955f7859 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 19 Jun 2023 15:32:07 +0300 Subject: [PATCH 21/28] rewrite parameter management MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- system/autoware_auto_msgs_adapter/README.md | 11 ++-- .../autoware_auto_msgs_adapter_core.hpp | 10 ++++ .../autoware_auto_msgs_adapter.schema.json | 43 ++++++++++++++++ .../src/autoware_auto_msgs_adapter_core.cpp | 50 ++++++++++++++++--- 4 files changed, 105 insertions(+), 9 deletions(-) create mode 100644 system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json diff --git a/system/autoware_auto_msgs_adapter/README.md b/system/autoware_auto_msgs_adapter/README.md index 26fadf6cd0b93..bb71eb44eaf63 100644 --- a/system/autoware_auto_msgs_adapter/README.md +++ b/system/autoware_auto_msgs_adapter/README.md @@ -34,8 +34,11 @@ in the `autoware_auto_msgs_adapter/config` directory. Example configuration: Set the `msg_type_target` parameter to the desired target message type from `autoware_auto_msgs`. -Make sure that the `msg_type_target` has the correspondence -in [src/autoware_auto_msgs_adapter_core.cpp](src/autoware_auto_msgs_adapter_core.cpp). +Make sure that the `msg_type_target` has the correspondence in either: +- [schema/autoware_auto_msgs_adapter.schema.json](schema/autoware_auto_msgs_adapter.schema.json) +- OR [src/autoware_auto_msgs_adapter_core.cpp](src/autoware_auto_msgs_adapter_core.cpp) `AutowareAutoMsgsAdapterNode::create_adapter_map()` method. + +(If this package is maintained correctly, they should match each other.) Launch the adapter node by any of the following methods: @@ -81,8 +84,10 @@ To add a new message pair, - Replicate and edit: - [adapter_control.hpp](include/autoware_auto_msgs_adapter/adapter_control.hpp). - Add the new header file to the [CMakeLists.txt](CMakeLists.txt). -- Add a new entry in the if-else if block in the constructor of the adapter node: +- Add a new entry to the returned map instance in the `AutowareAutoMsgsAdapterNode::create_adapter_map()` method of the adapter node: - [autoware_auto_msgs_adapter_core.cpp](src/autoware_auto_msgs_adapter_core.cpp) +- Add a new entry to the [schema/autoware_auto_msgs_adapter.schema.json](schema/autoware_auto_msgs_adapter.schema.json) file in the `definitions:autoware_auto_msgs_adapter:properties:msg_type_target:enum` section. + - Learn more about JSON schema usage in [here](https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/parameters/#json-schema). - Create a new config file by replicating and editing: - [adapter_control.param.yaml](config/adapter_control.param.yaml) - Add a new test file by replicating and editing: diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp index debe969d6a0bb..1d83c97624eb9 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp @@ -27,9 +27,19 @@ class AutowareAutoMsgsAdapterNode : public rclcpp::Node { public: explicit AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptions & node_options); + using MapStringAdapter = std::map>; private: AdapterBaseInterface::SharedPtr adapter_; + + + MapStringAdapter create_adapter_map( + const std::string & topic_name_source, const std::string & topic_name_target); + + void print_adapter_options(const MapStringAdapter & map_adapter); + + bool initialize_adapter( + const MapStringAdapter & map_adapter, const std::string & msg_type_target); }; } // namespace autoware_auto_msgs_adapter diff --git a/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json b/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json new file mode 100644 index 0000000000000..37c526746ea0b --- /dev/null +++ b/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json @@ -0,0 +1,43 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for autoware_auto_msg_adapter", + "type": "object", + "definitions": { + "autoware_auto_msgs_adapter": { + "type": "object", + "properties": { + "msg_type_target": { + "type": "string", + "description": "Target message type", + "enum": [ + "autoware_auto_control_msgs/msg/AckermannControlCommand" + ], + "default": "autoware_auto_control_msgs/msg/AckermannControlCommand" + }, + "topic_name_source": { + "type": "string", + "description": "Topic name of the message to be converted.", + "default": "/control/command/control_cmd" + }, + "topic_name_target": { + "type": "string", + "description": "Target topic name which the message will be converted into.", + "default": "/control/command/control_cmd_auto" + } + }, + "required": ["msg_type_target", "topic_name_source", "topic_name_target"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/autoware_auto_msgs_adapter" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index 70a48965e8715..9e1cdc675416f 100644 --- a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -18,12 +18,16 @@ #include +#include + namespace autoware_auto_msgs_adapter { using autoware_auto_control_msgs::msg::AckermannControlCommand; using autoware_control_msgs::msg::Control; +using MapStringAdapter = AutowareAutoMsgsAdapterNode::MapStringAdapter; + AutowareAutoMsgsAdapterNode::AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptions & node_options) : rclcpp::Node("autoware_auto_msgs_adapter", node_options) { @@ -31,13 +35,47 @@ AutowareAutoMsgsAdapterNode::AutowareAutoMsgsAdapterNode(const rclcpp::NodeOptio const std::string topic_name_source = declare_parameter("topic_name_source"); const std::string topic_name_target = declare_parameter("topic_name_target"); - if (msg_type_target == "autoware_auto_control_msgs/msg/AckermannControlCommand") { - AdapterControl::SharedPtr adapter = - std::make_shared(*this, topic_name_source, topic_name_target); - adapter_ = std::static_pointer_cast(adapter); - } else { - RCLCPP_ERROR(get_logger(), "Unknown msg type: %s", msg_type_target.c_str()); + // Map of available adapters + auto map_adapter = create_adapter_map(topic_name_source, topic_name_target); + + print_adapter_options(map_adapter); + + // Initialize the adapter with the selected option + if (!initialize_adapter(map_adapter, msg_type_target)) { + RCLCPP_ERROR( + get_logger(), "Unknown msg type: %s. Please refer to previous log for available options.", + msg_type_target.c_str()); + } +} + +MapStringAdapter AutowareAutoMsgsAdapterNode::create_adapter_map( + const std::string & topic_name_source, const std::string & topic_name_target) +{ + return { + {"autoware_auto_control_msgs/msg/AckermannControlCommand", + [&] { + return std::static_pointer_cast( + std::make_shared(*this, topic_name_source, topic_name_target)); + }}, + }; +} + +void AutowareAutoMsgsAdapterNode::print_adapter_options(const MapStringAdapter & map_adapter) +{ + std::string std_options_available; + for (const auto & entry : map_adapter) { + std_options_available += entry.first + "\n"; } + RCLCPP_INFO( + get_logger(), "Available msg_type_target options:\n%s", std_options_available.c_str()); +} + +bool AutowareAutoMsgsAdapterNode::initialize_adapter( + const MapStringAdapter & map_adapter, const std::string & msg_type_target) +{ + auto it = map_adapter.find(msg_type_target); + adapter_ = (it != map_adapter.end()) ? it->second() : nullptr; + return adapter_ != nullptr; } } // namespace autoware_auto_msgs_adapter From 8de307925fae77bc9f21cb820314dd5802061bfd Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 19 Jun 2023 13:56:30 +0000 Subject: [PATCH 22/28] style(pre-commit): autofix --- system/autoware_auto_msgs_adapter/README.md | 1 + .../include/autoware_auto_msgs_adapter_core.hpp | 1 - .../schema/autoware_auto_msgs_adapter.schema.json | 4 +--- 3 files changed, 2 insertions(+), 4 deletions(-) diff --git a/system/autoware_auto_msgs_adapter/README.md b/system/autoware_auto_msgs_adapter/README.md index bb71eb44eaf63..85c2797074f1f 100644 --- a/system/autoware_auto_msgs_adapter/README.md +++ b/system/autoware_auto_msgs_adapter/README.md @@ -35,6 +35,7 @@ in the `autoware_auto_msgs_adapter/config` directory. Example configuration: Set the `msg_type_target` parameter to the desired target message type from `autoware_auto_msgs`. Make sure that the `msg_type_target` has the correspondence in either: + - [schema/autoware_auto_msgs_adapter.schema.json](schema/autoware_auto_msgs_adapter.schema.json) - OR [src/autoware_auto_msgs_adapter_core.cpp](src/autoware_auto_msgs_adapter_core.cpp) `AutowareAutoMsgsAdapterNode::create_adapter_map()` method. diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp index 1d83c97624eb9..122baf071abef 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp @@ -32,7 +32,6 @@ class AutowareAutoMsgsAdapterNode : public rclcpp::Node private: AdapterBaseInterface::SharedPtr adapter_; - MapStringAdapter create_adapter_map( const std::string & topic_name_source, const std::string & topic_name_target); diff --git a/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json b/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json index 37c526746ea0b..cf853ee1da130 100644 --- a/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json +++ b/system/autoware_auto_msgs_adapter/schema/autoware_auto_msgs_adapter.schema.json @@ -9,9 +9,7 @@ "msg_type_target": { "type": "string", "description": "Target message type", - "enum": [ - "autoware_auto_control_msgs/msg/AckermannControlCommand" - ], + "enum": ["autoware_auto_control_msgs/msg/AckermannControlCommand"], "default": "autoware_auto_control_msgs/msg/AckermannControlCommand" }, "topic_name_source": { From 2c5a965edac9a7d40133bf187de4043cb638ff90 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 19 Jun 2023 16:58:55 +0300 Subject: [PATCH 23/28] remove redundant target_include_directories MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- system/autoware_auto_msgs_adapter/CMakeLists.txt | 4 ---- 1 file changed, 4 deletions(-) diff --git a/system/autoware_auto_msgs_adapter/CMakeLists.txt b/system/autoware_auto_msgs_adapter/CMakeLists.txt index 194b2257ef8e6..4b3e1e79b6e6b 100644 --- a/system/autoware_auto_msgs_adapter/CMakeLists.txt +++ b/system/autoware_auto_msgs_adapter/CMakeLists.txt @@ -11,10 +11,6 @@ set(TEST_NAME test_${PROJECT_NAME}) ament_auto_add_library(${NODE_NAME} src/autoware_auto_msgs_adapter_core.cpp) -target_include_directories(${NODE_NAME} - PRIVATE - $) - rclcpp_components_register_node(${NODE_NAME} PLUGIN "autoware_auto_msgs_adapter::AutowareAutoMsgsAdapterNode" EXECUTABLE ${EXEC_NAME}) From d29afb63386ca7b9313f7c3d4b1b099ec8875c9d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 19 Jun 2023 17:37:48 +0300 Subject: [PATCH 24/28] put headers back in include/autoware_auto_msgs_adapter/* MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../include/{ => autoware_auto_msgs_adapter}/adapter_base.hpp | 2 +- .../adapter_base_interface.hpp | 0 .../{ => autoware_auto_msgs_adapter}/adapter_control.hpp | 2 +- .../autoware_auto_msgs_adapter_core.hpp | 2 +- .../src/autoware_auto_msgs_adapter_core.cpp | 4 ++-- .../test/test_msg_ackermann_control_command.cpp | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) rename system/autoware_auto_msgs_adapter/include/{ => autoware_auto_msgs_adapter}/adapter_base.hpp (96%) rename system/autoware_auto_msgs_adapter/include/{ => autoware_auto_msgs_adapter}/adapter_base_interface.hpp (100%) rename system/autoware_auto_msgs_adapter/include/{ => autoware_auto_msgs_adapter}/adapter_control.hpp (97%) rename system/autoware_auto_msgs_adapter/include/{ => autoware_auto_msgs_adapter}/autoware_auto_msgs_adapter_core.hpp (96%) diff --git a/system/autoware_auto_msgs_adapter/include/adapter_base.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp similarity index 96% rename from system/autoware_auto_msgs_adapter/include/adapter_base.hpp rename to system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp index f506d66b1d8b0..eb1379daf2876 100644 --- a/system/autoware_auto_msgs_adapter/include/adapter_base.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp @@ -14,7 +14,7 @@ #ifndef ADAPTER_BASE_HPP_ #define ADAPTER_BASE_HPP_ -#include "adapter_base_interface.hpp" +#include "autoware_auto_msgs_adapter/adapter_base_interface.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp similarity index 100% rename from system/autoware_auto_msgs_adapter/include/adapter_base_interface.hpp rename to system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp diff --git a/system/autoware_auto_msgs_adapter/include/adapter_control.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp similarity index 97% rename from system/autoware_auto_msgs_adapter/include/adapter_control.hpp rename to system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp index c02f4e03877a2..4aaa2d6407177 100644 --- a/system/autoware_auto_msgs_adapter/include/adapter_control.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp @@ -14,7 +14,7 @@ #ifndef ADAPTER_CONTROL_HPP_ #define ADAPTER_CONTROL_HPP_ -#include "adapter_base.hpp" +#include "autoware_auto_msgs_adapter/adapter_base.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp similarity index 96% rename from system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp rename to system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp index 122baf071abef..4f3c9c7988341 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ #define AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ -#include "adapter_control.hpp" +#include "autoware_auto_msgs_adapter/adapter_control.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index 9e1cdc675416f..68be328ee808e 100644 --- a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_auto_msgs_adapter_core.hpp" +#include "autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp" -#include "adapter_control.hpp" +#include "autoware_auto_msgs_adapter/adapter_control.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp b/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp index e33ae07e6aca1..dfbe07a71d1e3 100644 --- a/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp +++ b/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include From 14ce34fca6e193208e27ee1cb64fdc6747520a80 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 19 Jun 2023 14:39:21 +0000 Subject: [PATCH 25/28] style(pre-commit): autofix --- .../include/autoware_auto_msgs_adapter/adapter_base.hpp | 6 +++--- .../autoware_auto_msgs_adapter/adapter_base_interface.hpp | 6 +++--- .../include/autoware_auto_msgs_adapter/adapter_control.hpp | 6 +++--- .../autoware_auto_msgs_adapter_core.hpp | 6 +++--- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp index eb1379daf2876..05104985e39ba 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp @@ -11,8 +11,8 @@ // 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 ADAPTER_BASE_HPP_ -#define ADAPTER_BASE_HPP_ +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ #include "autoware_auto_msgs_adapter/adapter_base_interface.hpp" @@ -54,4 +54,4 @@ class AdapterBase : public AdapterBaseInterface } // namespace autoware_auto_msgs_adapter -#endif // ADAPTER_BASE_HPP_ +#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp index 606993332fc4a..e22b81e28f661 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp @@ -11,8 +11,8 @@ // 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 ADAPTER_BASE_INTERFACE_HPP_ -#define ADAPTER_BASE_INTERFACE_HPP_ +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ #include @@ -31,4 +31,4 @@ class AdapterBaseInterface } // namespace autoware_auto_msgs_adapter -#endif // ADAPTER_BASE_INTERFACE_HPP_ +#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp index 4aaa2d6407177..0204747438398 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp @@ -11,8 +11,8 @@ // 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 ADAPTER_CONTROL_HPP_ -#define ADAPTER_CONTROL_HPP_ +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ #include "autoware_auto_msgs_adapter/adapter_base.hpp" @@ -66,4 +66,4 @@ class AdapterControl }; } // namespace autoware_auto_msgs_adapter -#endif // ADAPTER_CONTROL_HPP_ +#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp index 4f3c9c7988341..159e636a05a10 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ #include "autoware_auto_msgs_adapter/adapter_control.hpp" @@ -42,4 +42,4 @@ class AutowareAutoMsgsAdapterNode : public rclcpp::Node }; } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#endif // AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ From 361dea59fa8cff125e393f2ff3c171f1f6d63e04 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 19 Jun 2023 17:45:09 +0300 Subject: [PATCH 26/28] add missing header MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_auto_msgs_adapter_core.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp index 159e636a05a10..8e89366878eae 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp @@ -19,6 +19,7 @@ #include #include +#include namespace autoware_auto_msgs_adapter { From 6f2319ebbf6dd6578ec52e1696a59e8996733e0f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 19 Jun 2023 17:54:20 +0300 Subject: [PATCH 27/28] reorganize header paths MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- system/autoware_auto_msgs_adapter/CMakeLists.txt | 5 +++++ .../src/autoware_auto_msgs_adapter_core.cpp | 4 ++-- .../include}/adapter_base.hpp | 2 +- .../include}/adapter_base_interface.hpp | 0 .../include}/adapter_control.hpp | 2 +- .../include}/autoware_auto_msgs_adapter_core.hpp | 2 +- .../test/test_msg_ackermann_control_command.cpp | 2 +- 7 files changed, 11 insertions(+), 6 deletions(-) rename system/autoware_auto_msgs_adapter/{include/autoware_auto_msgs_adapter => src/include}/adapter_base.hpp (96%) rename system/autoware_auto_msgs_adapter/{include/autoware_auto_msgs_adapter => src/include}/adapter_base_interface.hpp (100%) rename system/autoware_auto_msgs_adapter/{include/autoware_auto_msgs_adapter => src/include}/adapter_control.hpp (97%) rename system/autoware_auto_msgs_adapter/{include/autoware_auto_msgs_adapter => src/include}/autoware_auto_msgs_adapter_core.hpp (96%) diff --git a/system/autoware_auto_msgs_adapter/CMakeLists.txt b/system/autoware_auto_msgs_adapter/CMakeLists.txt index 4b3e1e79b6e6b..9b48112227cbe 100644 --- a/system/autoware_auto_msgs_adapter/CMakeLists.txt +++ b/system/autoware_auto_msgs_adapter/CMakeLists.txt @@ -9,6 +9,10 @@ set(EXEC_NAME ${PROJECT_NAME}_exe) set(TEST_NAME test_${PROJECT_NAME}) ament_auto_add_library(${NODE_NAME} + src/include/adapter_base.hpp + src/include/adapter_base_interface.hpp + src/include/adapter_control.hpp + src/include/autoware_auto_msgs_adapter_core.hpp src/autoware_auto_msgs_adapter_core.cpp) rclcpp_components_register_node(${NODE_NAME} @@ -18,6 +22,7 @@ rclcpp_components_register_node(${NODE_NAME} if(BUILD_TESTING) file(GLOB_RECURSE TEST_SOURCES test/*.cpp) ament_add_ros_isolated_gtest(${TEST_NAME} ${TEST_SOURCES}) + target_include_directories(${TEST_NAME} PRIVATE src/include) target_link_libraries(${TEST_NAME} ${NODE_NAME}) endif() diff --git a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp index 68be328ee808e..98fe916903a60 100644 --- a/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp +++ b/system/autoware_auto_msgs_adapter/src/autoware_auto_msgs_adapter_core.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp" +#include "include/autoware_auto_msgs_adapter_core.hpp" -#include "autoware_auto_msgs_adapter/adapter_control.hpp" +#include "include/adapter_control.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp b/system/autoware_auto_msgs_adapter/src/include/adapter_base.hpp similarity index 96% rename from system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp rename to system/autoware_auto_msgs_adapter/src/include/adapter_base.hpp index 05104985e39ba..6ba81d169ecec 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/adapter_base.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ #define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ -#include "autoware_auto_msgs_adapter/adapter_base_interface.hpp" +#include "adapter_base_interface.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp b/system/autoware_auto_msgs_adapter/src/include/adapter_base_interface.hpp similarity index 100% rename from system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_base_interface.hpp rename to system/autoware_auto_msgs_adapter/src/include/adapter_base_interface.hpp diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp b/system/autoware_auto_msgs_adapter/src/include/adapter_control.hpp similarity index 97% rename from system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp rename to system/autoware_auto_msgs_adapter/src/include/adapter_control.hpp index 0204747438398..96ff0e297eeef 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/adapter_control.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/adapter_control.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ #define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ -#include "autoware_auto_msgs_adapter/adapter_base.hpp" +#include "adapter_base.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp similarity index 96% rename from system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp rename to system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp index 8e89366878eae..7c0e34679aa97 100644 --- a/system/autoware_auto_msgs_adapter/include/autoware_auto_msgs_adapter/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp @@ -14,7 +14,7 @@ #ifndef AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ #define AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ -#include "autoware_auto_msgs_adapter/adapter_control.hpp" +#include "adapter_control.hpp" #include diff --git a/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp b/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp index dfbe07a71d1e3..e33ae07e6aca1 100644 --- a/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp +++ b/system/autoware_auto_msgs_adapter/test/test_msg_ackermann_control_command.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include From 9e4e50dbf9f0b52c614da920f67aeff1bc273b8a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 19 Jun 2023 14:57:49 +0000 Subject: [PATCH 28/28] style(pre-commit): autofix --- .../autoware_auto_msgs_adapter/src/include/adapter_base.hpp | 6 +++--- .../src/include/adapter_base_interface.hpp | 6 +++--- .../src/include/adapter_control.hpp | 6 +++--- .../src/include/autoware_auto_msgs_adapter_core.hpp | 6 +++--- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/system/autoware_auto_msgs_adapter/src/include/adapter_base.hpp b/system/autoware_auto_msgs_adapter/src/include/adapter_base.hpp index 6ba81d169ecec..f506d66b1d8b0 100644 --- a/system/autoware_auto_msgs_adapter/src/include/adapter_base.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/adapter_base.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ +#ifndef ADAPTER_BASE_HPP_ +#define ADAPTER_BASE_HPP_ #include "adapter_base_interface.hpp" @@ -54,4 +54,4 @@ class AdapterBase : public AdapterBaseInterface } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_HPP_ +#endif // ADAPTER_BASE_HPP_ diff --git a/system/autoware_auto_msgs_adapter/src/include/adapter_base_interface.hpp b/system/autoware_auto_msgs_adapter/src/include/adapter_base_interface.hpp index e22b81e28f661..606993332fc4a 100644 --- a/system/autoware_auto_msgs_adapter/src/include/adapter_base_interface.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/adapter_base_interface.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ +#ifndef ADAPTER_BASE_INTERFACE_HPP_ +#define ADAPTER_BASE_INTERFACE_HPP_ #include @@ -31,4 +31,4 @@ class AdapterBaseInterface } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_BASE_INTERFACE_HPP_ +#endif // ADAPTER_BASE_INTERFACE_HPP_ diff --git a/system/autoware_auto_msgs_adapter/src/include/adapter_control.hpp b/system/autoware_auto_msgs_adapter/src/include/adapter_control.hpp index 96ff0e297eeef..c02f4e03877a2 100644 --- a/system/autoware_auto_msgs_adapter/src/include/adapter_control.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/adapter_control.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ +#ifndef ADAPTER_CONTROL_HPP_ +#define ADAPTER_CONTROL_HPP_ #include "adapter_base.hpp" @@ -66,4 +66,4 @@ class AdapterControl }; } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER__ADAPTER_CONTROL_HPP_ +#endif // ADAPTER_CONTROL_HPP_ diff --git a/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp b/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp index 7c0e34679aa97..a33a88c68618f 100644 --- a/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp +++ b/system/autoware_auto_msgs_adapter/src/include/autoware_auto_msgs_adapter_core.hpp @@ -11,8 +11,8 @@ // 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 AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ -#define AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#ifndef AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#define AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ #include "adapter_control.hpp" @@ -43,4 +43,4 @@ class AutowareAutoMsgsAdapterNode : public rclcpp::Node }; } // namespace autoware_auto_msgs_adapter -#endif // AUTOWARE_AUTO_MSGS_ADAPTER__AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_ +#endif // AUTOWARE_AUTO_MSGS_ADAPTER_CORE_HPP_