Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Switching to examples_interfaces #377

Open
wants to merge 4 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@

import unittest

from example_interfaces.msg import String
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i believe this changes led to https://ci.ros2.org/job/ci_linux/20965/testReport/junit/launch_testing_examples.launch_testing_examples/check_msgs_launch_test/launch_testing_examples_check_msgs_launch_test/.

this is because message type does not match anymore,

demo_nodes_cpp uses std_msgs/String, so i think this change requires the same change to https://github.com/ros2/demos

import launch
import launch.actions
import launch_ros.actions
import launch_testing.actions
import launch_testing.markers
from launch_testing_ros import WaitForTopics
import pytest
from std_msgs.msg import String


@pytest.mark.launch_test
Expand Down
2 changes: 1 addition & 1 deletion launch_testing/launch_testing_examples/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
<exec_depend>rclpy</exec_depend>
<exec_depend>rcl_interfaces</exec_depend>
<exec_depend>ros2bag</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>example_interfaces</exec_depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/composition/minimal_composition/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(example_interfaces REQUIRED)

include_directories(include)

Expand All @@ -23,7 +23,7 @@ add_library(composition_nodes SHARED
src/subscriber_node.cpp)
target_compile_definitions(composition_nodes
PRIVATE "MINIMAL_COMPOSITION_DLL")
ament_target_dependencies(composition_nodes rclcpp rclcpp_components std_msgs)
ament_target_dependencies(composition_nodes rclcpp rclcpp_components example_interfaces)

# This package installs libraries without exporting them.
# Export the library path to ensure that the installed libraries are available.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#define MINIMAL_COMPOSITION__PUBLISHER_NODE_HPP_

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "example_interfaces/msg/string.hpp"
#include "minimal_composition/visibility.h"

class PublisherNode : public rclcpp::Node
Expand All @@ -27,7 +27,7 @@ class PublisherNode : public rclcpp::Node
private:
void on_timer();
size_t count_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
rclcpp::Publisher<example_interfaces::msg::String>::SharedPtr publisher_;
rclcpp::TimerBase::SharedPtr timer_;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#define MINIMAL_COMPOSITION__SUBSCRIBER_NODE_HPP_

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "example_interfaces/msg/string.hpp"
#include "minimal_composition/visibility.h"

class SubscriberNode : public rclcpp::Node
Expand All @@ -25,7 +25,7 @@ class SubscriberNode : public rclcpp::Node
MINIMAL_COMPOSITION_PUBLIC SubscriberNode(rclcpp::NodeOptions options);

private:
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
rclcpp::Subscription<example_interfaces::msg::String>::SharedPtr subscription_;
};

#endif // MINIMAL_COMPOSITION__SUBSCRIBER_NODE_HPP_
4 changes: 2 additions & 2 deletions rclcpp/composition/minimal_composition/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,11 @@

<build_depend>rclcpp</build_depend>
<build_depend>rclcpp_components</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>example_interfaces</build_depend>

<exec_depend>rclcpp</exec_depend>
<exec_depend>rclcpp_components</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>example_interfaces</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,21 +16,21 @@

#include "minimal_composition/publisher_node.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "example_interfaces/msg/string.hpp"

using namespace std::chrono_literals;

PublisherNode::PublisherNode(rclcpp::NodeOptions options)
: Node("publisher_node", options), count_(0)
{
publisher_ = create_publisher<std_msgs::msg::String>("topic", 10);
publisher_ = create_publisher<example_interfaces::msg::String>("topic", 10);
timer_ = create_wall_timer(
500ms, std::bind(&PublisherNode::on_timer, this));
}

void PublisherNode::on_timer()
{
auto message = std_msgs::msg::String();
auto message = example_interfaces::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Publisher: '%s'", message.data.c_str());
publisher_->publish(message);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,15 @@

#include "minimal_composition/subscriber_node.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "example_interfaces/msg/string.hpp"

SubscriberNode::SubscriberNode(rclcpp::NodeOptions options)
: Node("subscriber_node", options)
{
subscription_ = create_subscription<std_msgs::msg::String>(
subscription_ = create_subscription<example_interfaces::msg::String>(
"topic",
10,
[this](std_msgs::msg::String::UniquePtr msg) {
[this](example_interfaces::msg::String::UniquePtr msg) {
RCLCPP_INFO(this->get_logger(), "Subscriber: '%s'", msg->data.c_str());
});
}
Expand Down
10 changes: 5 additions & 5 deletions rclcpp/executors/cbg_executor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,23 +13,23 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(example_interfaces REQUIRED)

add_executable(
ping
src/ping.cpp
src/examples_rclcpp_cbg_executor/ping_node.cpp
)
target_include_directories(ping PUBLIC include)
ament_target_dependencies(ping rclcpp std_msgs)
ament_target_dependencies(ping rclcpp example_interfaces)

add_executable(
pong
src/pong.cpp
src/examples_rclcpp_cbg_executor/pong_node.cpp
)
target_include_directories(pong PUBLIC include)
ament_target_dependencies(pong rclcpp std_msgs)
ament_target_dependencies(pong rclcpp example_interfaces)

add_executable(
ping_pong
Expand All @@ -38,7 +38,7 @@ add_executable(
src/examples_rclcpp_cbg_executor/pong_node.cpp
)
target_include_directories(ping_pong PUBLIC include)
ament_target_dependencies(ping_pong rclcpp std_msgs)
ament_target_dependencies(ping_pong rclcpp example_interfaces)

install(TARGETS ping pong ping_pong
DESTINATION lib/${PROJECT_NAME}
Expand All @@ -52,5 +52,5 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()

ament_export_dependencies(rclcpp std_msgs)
ament_export_dependencies(rclcpp example_interfaces)
ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/int32.hpp"
#include "example_interfaces/msg/int32.hpp"

namespace examples_rclcpp_cbg_executor
{
Expand All @@ -47,15 +47,15 @@ class PingNode : public rclcpp::Node

private:
rclcpp::TimerBase::SharedPtr ping_timer_;
rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr high_ping_publisher_;
rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr low_ping_publisher_;
rclcpp::Publisher<example_interfaces::msg::Int32>::SharedPtr high_ping_publisher_;
rclcpp::Publisher<example_interfaces::msg::Int32>::SharedPtr low_ping_publisher_;
void send_ping();

rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr high_pong_subscription_;
void high_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg);
rclcpp::Subscription<example_interfaces::msg::Int32>::SharedPtr high_pong_subscription_;
void high_pong_received(const example_interfaces::msg::Int32::ConstSharedPtr msg);

rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr low_pong_subscription_;
void low_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg);
rclcpp::Subscription<example_interfaces::msg::Int32>::SharedPtr low_pong_subscription_;
void low_pong_received(const example_interfaces::msg::Int32::ConstSharedPtr msg);

std::vector<RTTData> rtt_data_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/int32.hpp"
#include "example_interfaces/msg/int32.hpp"

namespace examples_rclcpp_cbg_executor
{
Expand All @@ -39,13 +39,13 @@ class PongNode : public rclcpp::Node
private:
rclcpp::CallbackGroup::SharedPtr low_prio_callback_group_;

rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr high_ping_subscription_;
rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr high_pong_publisher_;
void high_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg);
rclcpp::Subscription<example_interfaces::msg::Int32>::SharedPtr high_ping_subscription_;
rclcpp::Publisher<example_interfaces::msg::Int32>::SharedPtr high_pong_publisher_;
void high_ping_received(const example_interfaces::msg::Int32::ConstSharedPtr msg);

rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr low_ping_subscription_;
rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr low_pong_publisher_;
void low_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg);
rclcpp::Subscription<example_interfaces::msg::Int32>::SharedPtr low_ping_subscription_;
rclcpp::Publisher<example_interfaces::msg::Int32>::SharedPtr low_pong_publisher_;
void low_ping_received(const example_interfaces::msg::Int32::ConstSharedPtr msg);

static void burn_cpu_cycles(std::chrono::nanoseconds duration);
};
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/executors/cbg_executor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>std_msgs</depend>
<depend>example_interfaces</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ PingNode::PingNode()
: rclcpp::Node("ping_node")
{
using std::placeholders::_1;
using std_msgs::msg::Int32;
using example_interfaces::msg::Int32;

this->declare_parameter<double>("ping_period", 0.01);
std::chrono::nanoseconds ping_period = get_nanos_from_secs_parameter(this, "ping_period");
Expand All @@ -45,19 +45,19 @@ PingNode::PingNode()

void PingNode::send_ping()
{
std_msgs::msg::Int32 msg;
example_interfaces::msg::Int32 msg;
msg.data = static_cast<int32_t>(rtt_data_.size());
rtt_data_.push_back(RTTData(now()));
high_ping_publisher_->publish(msg);
low_ping_publisher_->publish(msg);
}

void PingNode::high_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg)
void PingNode::high_pong_received(const example_interfaces::msg::Int32::ConstSharedPtr msg)
{
rtt_data_[msg->data].high_received_ = now();
}

void PingNode::low_pong_received(const std_msgs::msg::Int32::ConstSharedPtr msg)
void PingNode::low_pong_received(const example_interfaces::msg::Int32::ConstSharedPtr msg)
{
rtt_data_[msg->data].low_received_ = now();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ PongNode::PongNode()
: rclcpp::Node("pong_node")
{
using std::placeholders::_1;
using std_msgs::msg::Int32;
using example_interfaces::msg::Int32;

declare_parameter<double>("high_busyloop", 0.01);
high_pong_publisher_ = this->create_publisher<Int32>("high_pong", rclcpp::SensorDataQoS());
Expand Down Expand Up @@ -58,14 +58,14 @@ rclcpp::CallbackGroup::SharedPtr PongNode::get_low_prio_callback_group()
return low_prio_callback_group_; // the second callback group created in the ctor.
}

void PongNode::high_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg)
void PongNode::high_ping_received(const example_interfaces::msg::Int32::ConstSharedPtr msg)
{
std::chrono::nanoseconds busyloop = get_nanos_from_secs_parameter(this, "high_busyloop");
burn_cpu_cycles(busyloop);
high_pong_publisher_->publish(*msg);
}

void PongNode::low_ping_received(const std_msgs::msg::Int32::ConstSharedPtr msg)
void PongNode::low_ping_received(const example_interfaces::msg::Int32::ConstSharedPtr msg)
{
std::chrono::nanoseconds busyloop = get_nanos_from_secs_parameter(this, "low_busyloop");
burn_cpu_cycles(busyloop);
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/executors/multithreaded_executor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(example_interfaces REQUIRED)

add_executable(multithreaded_executor multithreaded_executor.cpp)
ament_target_dependencies(multithreaded_executor rclcpp std_msgs)
ament_target_dependencies(multithreaded_executor rclcpp example_interfaces)

install(TARGETS
multithreaded_executor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <thread>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "example_interfaces/msg/string.hpp"

using namespace std::chrono_literals;

Expand All @@ -42,10 +42,10 @@ class PublisherNode : public rclcpp::Node
PublisherNode()
: Node("PublisherNode"), count_(0)
{
publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
publisher_ = this->create_publisher<example_interfaces::msg::String>("topic", 10);
auto timer_callback =
[this]() -> void {
auto message = std_msgs::msg::String();
auto message = example_interfaces::msg::String();
message.data = "Hello World! " + std::to_string(this->count_++);

// Extract current thread
Expand All @@ -62,7 +62,7 @@ class PublisherNode : public rclcpp::Node

private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
rclcpp::Publisher<example_interfaces::msg::String>::SharedPtr publisher_;
size_t count_;
};

Expand All @@ -88,7 +88,7 @@ class DualThreadedNode : public rclcpp::Node
auto sub2_opt = rclcpp::SubscriptionOptions();
sub2_opt.callback_group = callback_group_subscriber2_;

subscription1_ = this->create_subscription<std_msgs::msg::String>(
subscription1_ = this->create_subscription<example_interfaces::msg::String>(
"topic",
rclcpp::QoS(10),
// std::bind is sort of C++'s way of passing a function
Expand All @@ -104,7 +104,7 @@ class DualThreadedNode : public rclcpp::Node
sub1_opt); // This is where we set the callback group.
// This subscription will run with callback group subscriber1

subscription2_ = this->create_subscription<std_msgs::msg::String>(
subscription2_ = this->create_subscription<example_interfaces::msg::String>(
"topic",
rclcpp::QoS(10),
std::bind(
Expand All @@ -129,7 +129,7 @@ class DualThreadedNode : public rclcpp::Node
* Every time the Publisher publishes something, all subscribers to the topic get poked
* This function gets called when Subscriber1 is poked (due to the std::bind we used when defining it)
*/
void subscriber1_cb(const std_msgs::msg::String::ConstSharedPtr msg)
void subscriber1_cb(const example_interfaces::msg::String::ConstSharedPtr msg)
{
auto message_received_at = timing_string();

Expand All @@ -143,7 +143,7 @@ class DualThreadedNode : public rclcpp::Node
* This function gets called when Subscriber2 is poked
* Since it's running on a separate thread than Subscriber 1, it will run at (more-or-less) the same time!
*/
void subscriber2_cb(const std_msgs::msg::String::ConstSharedPtr msg)
void subscriber2_cb(const example_interfaces::msg::String::ConstSharedPtr msg)
{
auto message_received_at = timing_string();

Expand All @@ -155,8 +155,8 @@ class DualThreadedNode : public rclcpp::Node

rclcpp::CallbackGroup::SharedPtr callback_group_subscriber1_;
rclcpp::CallbackGroup::SharedPtr callback_group_subscriber2_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription1_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription2_;
rclcpp::Subscription<example_interfaces::msg::String>::SharedPtr subscription1_;
rclcpp::Subscription<example_interfaces::msg::String>::SharedPtr subscription2_;
};

int main(int argc, char * argv[])
Expand Down
Loading