Skip to content

Commit

Permalink
create simple_int_subscriber pkg
Browse files Browse the repository at this point in the history
Signed-off-by: Autumn60 <[email protected]>
  • Loading branch information
Autumn60 committed Jul 5, 2024
1 parent d7523ac commit 37069a3
Show file tree
Hide file tree
Showing 5 changed files with 113 additions and 0 deletions.
33 changes: 33 additions & 0 deletions src/sample/simple_int_subscriber/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
cmake_minimum_required(VERSION 3.5)
project(simple_int_subscriber)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

ament_auto_add_library(simple_int_subscriber SHARED
src/simple_int_subscriber.cpp
)

rclcpp_components_register_node(simple_int_subscriber
PLUGIN "simple_int_subscriber::SimpleIntSubscriber"
EXECUTABLE simple_int_subscriber_node
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_auto_package(INSTALL_TO_SHARE
launch
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
#ifndef SIMPLE_INT_SUBSCRIBER__SIMPLE_INT_SUBSCRIBER_HPP_
#define SIMPLE_INT_SUBSCRIBER__SIMPLE_INT_SUBSCRIBER_HPP_

#include <rclcpp/rclcpp.hpp>

#include <std_msgs/msg/int32.hpp>

namespace simple_int_subscriber
{

using Int32 = std_msgs::msg::Int32;

using Int32Subscription = rclcpp::Subscription<Int32>;

class SimpleIntSubscriber : public rclcpp::Node
{
public:
explicit SimpleIntSubscriber(const rclcpp::NodeOptions & options);

private:
void callback(const Int32::SharedPtr msg);

Int32Subscription::SharedPtr sub_;
};

} // namespace simple_int_subscriber

#endif // SIMPLE_INT_SUBSCRIBER__SIMPLE_INT_SUBSCRIBER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<launch>
<arg name="topic" default="/sample/int"/>

<node pkg="simple_int_subscriber" name="simple_int_subscriber" exec="simple_int_subscriber_node" output="screen">
<remap from="~/input/int" to="$(var topic)"/>
</node>
</launch>
21 changes: 21 additions & 0 deletions src/sample/simple_int_subscriber/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>simple_int_subscriber</name>
<version>0.0.0</version>
<description>The simple_int_subscriber package</description>
<maintainer email="[email protected]">Akiro Harada</maintainer>

<license>Apache 2</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>std_msgs</depend>
<test_depend>ament_lint_auto</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
24 changes: 24 additions & 0 deletions src/sample/simple_int_subscriber/src/simple_int_subscriber.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#include "simple_int_subscriber/simple_int_subscriber.hpp"

namespace simple_int_subscriber
{

SimpleIntSubscriber::SimpleIntSubscriber(const rclcpp::NodeOptions & options)
: Node("simple_int_subscriber", options)
{
// Declare Subscribers
{
sub_ = this->create_subscription<Int32>(
"~/input/int", 1, [this](const Int32::SharedPtr msg) { this->callback(msg); });
}
}

void SimpleIntSubscriber::callback(const Int32::SharedPtr msg)
{
std::cout << "Received: '" << msg->data << "'" << std::endl;
}

} // namespace simple_int_subscriber

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(simple_int_subscriber::SimpleIntSubscriber)

0 comments on commit 37069a3

Please sign in to comment.