--- /dev/null
+root = true
+
+[*.{cc,hh}]
+end_of_line = lf
+insert_final_newline = true
+charset = utf-8
+trim_trailing_whitespace = true
+indent_style = tab
+indent_size = 8
+max_line_length = 79
+
+[*.{py,md}]
+end_of_line = lf
+insert_final_newline = true
+charset = utf-8
+trim_trailing_whitespace = true
+indent_style = space
+indent_size = 4
+max_line_length = 79
+
+[*.{xml,txt}]
+end_of_line = lf
+insert_final_newline = true
+charset = utf-8
+trim_trailing_whitespace = true
+indent_style = space
+indent_size = 2
+max_line_length = 79
--- /dev/null
+cmake_minimum_required(VERSION 3.8)
+project(wrrr)
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-Wall -Wextra -Wpedantic)
+endif()
+
+find_package(ament_cmake REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(nav_msgs REQUIRED)
+
+include_directories(include)
+
+add_executable(rrts src/rrts_wr.cc)
+ament_target_dependencies(rrts rclcpp nav_msgs)
+install(TARGETS rrts DESTINATION lib/${PROJECT_NAME})
+
+ament_package()
--- /dev/null
+<?xml version="1.0"?>
+<?xml-model
+ href="http://download.ros.org/schema/package_format3.xsd"
+ schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+ <name>wrrr</name>
+ <version>0.1.0</version>
+ <description>Wrap rrts (RRT planning alg.) to ROS 2.</description>
+ <maintainer email="jiri.vlasak.2@cvut.cz">Jiri Vlasak</maintainer>
+ <license>GPL-3.0-only</license>
+
+ <buildtool_depend>ament_cmake</buildtool_depend>
+ <buildtool_depend>rclcpp</buildtool_depend>
+ <buildtool_depend>nav_msgs</buildtool_depend>
+
+ <export>
+ <build_type>ament_cmake</build_type>
+ </export>
+</package>
--- /dev/null
+#include "rclcpp/rclcpp.hpp"
+#include "nav_msgs/srv/get_plan.hpp"
+
+void
+plan_path(const std::shared_ptr<nav_msgs::srv::GetPlan::Request> req,
+ std::shared_ptr<nav_msgs::srv::GetPlan::Response> res)
+{
+ RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
+ "received req, needs to process it.");
+}
+
+int
+main(int argc, char **argv)
+{
+ rclcpp::init(argc, argv);
+ auto node = rclcpp::Node::make_shared("rrts");
+ auto srv = node->create_service<nav_msgs::srv::GetPlan>("rrts/planner",
+ &plan_path);
+ RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to plan paths.");
+ rclcpp::spin(node);
+ rclcpp::shutdown();
+ return 0;
+}