Skip to content

Commit

Permalink
Add test for GenericPublisher/Subscriber (#97)
Browse files Browse the repository at this point in the history
Signed-off-by: h-suzuki <[email protected]>
Signed-off-by: h-suzuki-isp <[email protected]>
  • Loading branch information
h-suzuki-isp committed Apr 5, 2024
1 parent e4f1e7f commit a689891
Show file tree
Hide file tree
Showing 5 changed files with 833 additions and 0 deletions.
22 changes: 22 additions & 0 deletions test_tracetools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,24 @@ if(BUILD_TESTING)
${std_msgs_TARGETS}
)

add_executable(test_generic_ping
src/test_generic_ping.cpp
)
target_link_libraries(test_generic_ping PRIVATE
${PROJECT_NAME}_mark_process
rclcpp::rclcpp
${std_msgs_TARGETS}
)

add_executable(test_generic_pong
src/test_generic_pong.cpp
)
target_link_libraries(test_generic_pong PRIVATE
${PROJECT_NAME}_mark_process
rclcpp::rclcpp
${std_msgs_TARGETS}
)

add_executable(test_timer
src/test_timer.cpp
)
Expand Down Expand Up @@ -147,6 +165,8 @@ if(BUILD_TESTING)
test_lifecycle_client
test_ping
test_pong
test_generic_ping
test_generic_pong
test_publisher
test_service_ping
test_service_pong
Expand Down Expand Up @@ -180,9 +200,11 @@ if(BUILD_TESTING)
test/test_lifecycle_node.py
test/test_node.py
test/test_pub_sub.py
test/test_generic_pub_sub.py
test/test_publisher.py
test/test_service.py
test/test_subscription.py
test/test_generic_subscription.py
test/test_timer.py
)
foreach(_test_path ${_test_tracetools_pytest_tests})
Expand Down
105 changes: 105 additions & 0 deletions test_tracetools/src/test_generic_ping.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,105 @@
// Copyright 2019 Robert Bosch GmbH
// Copyright 2024 TIER IV, Inc.
//
// 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 <memory>
#include <chrono>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "test_tracetools/mark_process.hpp"

using namespace std::chrono_literals;

#define NODE_NAME "test_generic_ping"
#define SUB_TOPIC_NAME "pong"
#define PUB_TOPIC_NAME "ping"
#define QUEUE_DEPTH 10

class PingNode : public rclcpp::Node
{
public:
PingNode(rclcpp::NodeOptions options, bool do_only_one)
: Node(NODE_NAME, options), do_only_one_(do_only_one)
{
sub_ = this->create_generic_subscription(
SUB_TOPIC_NAME,
"std_msgs/msg/String",
rclcpp::QoS(QUEUE_DEPTH),
std::bind(&PingNode::callback, this, std::placeholders::_1));
pub_ = this->create_generic_publisher(
PUB_TOPIC_NAME,
"std_msgs/msg/String",
rclcpp::QoS(QUEUE_DEPTH));
timer_ = this->create_wall_timer(
500ms,
std::bind(&PingNode::timer_callback, this));
serializer_ = std::make_shared<rclcpp::Serialization<std_msgs::msg::String>>();
}

explicit PingNode(rclcpp::NodeOptions options)
: PingNode(options, true) {}

private:
void callback(std::shared_ptr<rclcpp::SerializedMessage> serialized_msg)
{
std_msgs::msg::String deserialized_msg;
serializer_->deserialize_message(serialized_msg.get(), &deserialized_msg);
RCLCPP_INFO(this->get_logger(), "[output] %s", deserialized_msg.data.c_str());
if (do_only_one_) {
rclcpp::shutdown();
}
}

void timer_callback()
{
std_msgs::msg::String msg;
msg.data = "some random ping string";
rclcpp::SerializedMessage serialized_msg;
serialized_msg.reserve(1024);
serializer_->serialize_message(&msg, &serialized_msg);
pub_->publish(serialized_msg);
}

rclcpp::GenericSubscription::SharedPtr sub_;
rclcpp::GenericPublisher::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_;
std::shared_ptr<rclcpp::Serialization<std_msgs::msg::String>> serializer_;
bool do_only_one_;
};

int main(int argc, char * argv[])
{
test_tracetools::mark_trace_test_process();

bool do_only_one = true;
for (int i = 0; i < argc; ++i) {
if (strncmp(argv[i], "do_more", 7) == 0) {
do_only_one = false;
}
}

rclcpp::init(argc, argv);

rclcpp::executors::SingleThreadedExecutor exec;
auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions(), do_only_one);
exec.add_node(ping_node);

printf("spinning\n");
exec.spin();

// Will actually be called inside the node's callback
rclcpp::shutdown();
return 0;
}
93 changes: 93 additions & 0 deletions test_tracetools/src/test_generic_pong.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
// Copyright 2019 Robert Bosch GmbH
// Copyright 2024 TIER IV, Inc.
//
// 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 <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "test_tracetools/mark_process.hpp"

#define NODE_NAME "test_generic_pong"
#define SUB_TOPIC_NAME "ping"
#define PUB_TOPIC_NAME "pong"

class PongNode : public rclcpp::Node
{
public:
PongNode(rclcpp::NodeOptions options, bool do_only_one)
: Node(NODE_NAME, options), do_only_one_(do_only_one)
{
sub_ = this->create_generic_subscription(
SUB_TOPIC_NAME,
"std_msgs/msg/String",
rclcpp::QoS(10),
std::bind(&PongNode::callback, this, std::placeholders::_1));
pub_ = this->create_generic_publisher(
PUB_TOPIC_NAME,
"std_msgs/msg/String",
rclcpp::QoS(10));
serializer_ = std::make_shared<rclcpp::Serialization<std_msgs::msg::String>>();
}

explicit PongNode(rclcpp::NodeOptions options)
: PongNode(options, true) {}

private:
void callback(std::shared_ptr<rclcpp::SerializedMessage> msg)
{
std_msgs::msg::String deserialized_msg;
serializer_->deserialize_message(msg.get(), &deserialized_msg);
RCLCPP_INFO(this->get_logger(), "[output] %s", deserialized_msg.data.c_str());
std_msgs::msg::String next_msg;
next_msg.data = "some random pong string";
rclcpp::SerializedMessage serialized_msg;
serialized_msg.reserve(1024);
serializer_->serialize_message(&next_msg, &serialized_msg);
pub_->publish(serialized_msg);
if (do_only_one_) {
rclcpp::shutdown();
}
}

rclcpp::GenericSubscription::SharedPtr sub_;
rclcpp::GenericPublisher::SharedPtr pub_;
std::shared_ptr<rclcpp::Serialization<std_msgs::msg::String>> serializer_;
bool do_only_one_;
};

int main(int argc, char * argv[])
{
test_tracetools::mark_trace_test_process();

bool do_only_one = true;
for (int i = 0; i < argc; ++i) {
if (strncmp(argv[i], "do_more", 7) == 0) {
do_only_one = false;
}
}

rclcpp::init(argc, argv);

rclcpp::executors::SingleThreadedExecutor exec;
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions(), do_only_one);
exec.add_node(pong_node);

printf("spinning\n");
exec.spin();

// Will actually be called inside the node's callback
rclcpp::shutdown();
return 0;
}
Loading

0 comments on commit a689891

Please sign in to comment.