commit ae2875d7cfecc4f1c319dfef86985443fb0e2537 Author: James Pace Date: Tue Feb 7 00:45:20 2023 +0000 First commit of a simple package that can be used for demonstration. diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..09ada36 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.8) +project(j7s-simple) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) + +add_executable(j7s-publisher src/j7s-publisher.cpp) +target_include_directories(j7s-publisher PUBLIC + $ + $) +target_compile_features(j7s-publisher PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 +ament_target_dependencies(j7s-publisher rclcpp std_msgs) + +install(DIRECTORY + launch + DESTINATION share/${PROJECT_NAME}/ +) +install(TARGETS j7s-publisher + DESTINATION lib/${PROJECT_NAME}) + +ament_package() diff --git a/include/j7s-simple/j7s-publisher.hpp b/include/j7s-simple/j7s-publisher.hpp new file mode 100644 index 0000000..ee041b9 --- /dev/null +++ b/include/j7s-simple/j7s-publisher.hpp @@ -0,0 +1,26 @@ +// Copyright 2023 James Pace +// +// 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. +#pragma once + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + +class J7sPublisher: public rclcpp::Node +{ +public: + J7sPublisher(); +private: + rclcpp::TimerBase::SharedPtr m_timer; + rclcpp::Publisher::SharedPtr m_publisher; +}; diff --git a/launch/j7s_publisher_launch.py b/launch/j7s_publisher_launch.py new file mode 100644 index 0000000..b7d6fa2 --- /dev/null +++ b/launch/j7s_publisher_launch.py @@ -0,0 +1,10 @@ +import launch +import launch_ros.actions + +def generate_launch_description(): + return launch.LaunchDescription([ + launch_ros.actions.Node( + package='j7s-simple', + executable='j7s-publisher', + name='j7s_publisher') + ]) diff --git a/package.xml b/package.xml new file mode 100644 index 0000000..37f3843 --- /dev/null +++ b/package.xml @@ -0,0 +1,17 @@ + + + + j7s-simple + 0.0.0 + A set of simple nodes for testing things which package ros2. + James Pace + Apache-2.0 + + ament_cmake + std_msgs + rclcpp + + + ament_cmake + + diff --git a/src/j7s-publisher.cpp b/src/j7s-publisher.cpp new file mode 100644 index 0000000..bfe198b --- /dev/null +++ b/src/j7s-publisher.cpp @@ -0,0 +1,38 @@ +// Copyright 2023 James Pace +// +// 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 +using namespace std::chrono_literals; + + +J7sPublisher::J7sPublisher(): + Node("j7s_publisher") +{ + m_publisher = this->create_publisher("j7s_hello", 1); + const auto callback = [this]() { + std_msgs::msg::String msg; + msg.data = "Hello from j7s!"; + m_publisher->publish(msg); + }; + m_timer = this->create_wall_timer(500ms, callback); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +}