Skip to content
Merged
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
6 changes: 3 additions & 3 deletions .github/workflows/rolling.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,18 +14,18 @@ jobs:
runs-on: ${{ matrix.os }}
strategy:
matrix:
os: [ubuntu-22.04]
os: [ubuntu-24.04]
fail-fast: false
steps:
- uses: actions/checkout@v2
- name: Setup ROS 2
uses: ros-tooling/setup-ros@0.7.1
uses: ros-tooling/setup-ros@0.7.9
with:
required-ros-distributions: rolling
- name: Install deps for testing
run: sudo apt-get install ros-rolling-vision-msgs
- name: build and test
uses: ros-tooling/action-ros-ci@0.3.6
uses: ros-tooling/action-ros-ci@0.3.15
with:
package-name: cs4home_core
target-ros2-distro: rolling
Expand Down
4 changes: 3 additions & 1 deletion cs4home_core/include/cs4home_core/CognitiveModule.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,9 @@ class CognitiveModule : public rclcpp_lifecycle::LifecycleNode
using CallbackReturnT =
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

explicit CognitiveModule(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
explicit CognitiveModule(
const std::string & name,
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

CallbackReturnT on_configure(const rclcpp_lifecycle::State & state);
CallbackReturnT on_activate(const rclcpp_lifecycle::State & state);
Expand Down
18 changes: 10 additions & 8 deletions cs4home_core/src/cs4home_core/CognitiveModule.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,10 @@
namespace cs4home_core
{

CognitiveModule::CognitiveModule(const rclcpp::NodeOptions & options)
: LifecycleNode("cognitive_module", options)
CognitiveModule::CognitiveModule(
const std::string & name,
const rclcpp::NodeOptions & options)
: LifecycleNode(name, options)
{
declare_parameter("core", core_name_);
declare_parameter("afferent", afferent_name_);
Expand All @@ -45,8 +47,8 @@ CallbackReturnT CognitiveModule::on_configure(const rclcpp_lifecycle::State & st

get_parameter("efferent", efferent_name_);
std::string error_efferent;
std::tie(efferent_, error_efferent) = load_component<Efferent>(efferent_name_,
shared_from_this());
std::tie(efferent_, error_efferent) = load_component<Efferent>(
efferent_name_, shared_from_this());
if (efferent_ == nullptr || !efferent_->configure()) {
RCLCPP_ERROR(
get_logger(), "Error configuring efferent at %s with name %s: %s",
Expand All @@ -56,8 +58,8 @@ CallbackReturnT CognitiveModule::on_configure(const rclcpp_lifecycle::State & st

get_parameter("afferent", afferent_name_);
std::string error_afferent;
std::tie(afferent_, error_afferent) = load_component<Afferent>(afferent_name_,
shared_from_this());
std::tie(afferent_, error_afferent) = load_component<Afferent>(
afferent_name_, shared_from_this());
if (afferent_ == nullptr || !afferent_->configure()) {
RCLCPP_ERROR(
get_logger(), "Error configuring afferent at %s with name %s: %s",
Expand All @@ -80,8 +82,8 @@ CallbackReturnT CognitiveModule::on_configure(const rclcpp_lifecycle::State & st

get_parameter("coupling", coupling_name_);
std::string error_coupling;
std::tie(coupling_, error_coupling) = load_component<Coupling>(coupling_name_,
shared_from_this());
std::tie(coupling_, error_coupling) = load_component<Coupling>(
coupling_name_, shared_from_this());
if (coupling_ == nullptr || !coupling_->configure()) {
RCLCPP_ERROR(
get_logger(), "Error configuring efferent at %s with name %s: %s",
Expand Down
2 changes: 1 addition & 1 deletion cs4home_core/test/ImageFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class ImageFilter : public cs4home_core::Core
public:
RCLCPP_SMART_PTR_DEFINITIONS(ImageFilter)

explicit ImageFilter(rclcpp_lifecycle::LifecycleNode::SharedPtr parent)
explicit ImageFilter(rclcpp_lifecycle::LifecycleNode::SharedPtr parent)
: Core(parent)
{
RCLCPP_DEBUG(parent_->get_logger(), "Core created: [ImageFilter]");
Expand Down
2 changes: 1 addition & 1 deletion cs4home_core/test/ImageFilterCB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ class ImageFilterCB : public cs4home_core::Core
public:
RCLCPP_SMART_PTR_DEFINITIONS(ImageFilterCB)

explicit ImageFilterCB(rclcpp_lifecycle::LifecycleNode::SharedPtr parent)
explicit ImageFilterCB(rclcpp_lifecycle::LifecycleNode::SharedPtr parent)
: Core(parent)
{
RCLCPP_DEBUG(parent_->get_logger(), "Core created: [ImageFilterCB]");
Expand Down
6 changes: 3 additions & 3 deletions cs4home_core/test/SimpleImageInput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,9 @@ class SimpleImageInput : public cs4home_core::Afferent
std::string param_name = "simple_image_input.topics";
parent_->get_parameter(param_name, input_topic_names_);

RCLCPP_DEBUG(parent_->get_logger(), "[SimpleImageInput] Configuring %zu inputs [%s]",
input_topic_names_.size(),
param_name.c_str());
RCLCPP_DEBUG(
parent_->get_logger(), "[SimpleImageInput] Configuring %zu inputs [%s]",
input_topic_names_.size(), param_name.c_str());

for (size_t i = 0; i < input_topic_names_.size(); i++) {
if (create_subscriber(input_topic_names_[i], "sensor_msgs/msg/Image")) {
Expand Down
15 changes: 8 additions & 7 deletions cs4home_core/test/cognitive_module_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,8 @@ TEST(cognitive_module_test, afferent_on_subscription)
afferent->set_mode(cs4home_core::Afferent::CALLBACK);
ASSERT_EQ(afferent->get_mode(), cs4home_core::Afferent::ONDEMAND);

afferent->set_mode(cs4home_core::Afferent::CALLBACK,
afferent->set_mode(
cs4home_core::Afferent::CALLBACK,
[&images](std::unique_ptr<rclcpp::SerializedMessage> msg) {
images.push_back(std::move(msg));
}
Expand Down Expand Up @@ -150,7 +151,7 @@ TEST(cognitive_module_test, efferent)

std::vector<sensor_msgs::msg::Image> images;
auto sub = sub_node->create_subscription<sensor_msgs::msg::Image>(
"/image", 100, [&images] (sensor_msgs::msg::Image msg) {
"/image", 100, [&images](sensor_msgs::msg::Image msg) {
images.push_back(msg);
});

Expand Down Expand Up @@ -196,7 +197,7 @@ TEST(cognitive_module_test, core)

std::vector<sensor_msgs::msg::Image> images;
auto sub = sub_node->create_subscription<sensor_msgs::msg::Image>(
"/out_image", 100, [&images] (sensor_msgs::msg::Image msg) {
"/out_image", 100, [&images](sensor_msgs::msg::Image msg) {
images.push_back(msg);
});

Expand Down Expand Up @@ -257,7 +258,7 @@ TEST(cognitive_module_test, core_cb)

std::vector<sensor_msgs::msg::Image> images;
auto sub = sub_node->create_subscription<sensor_msgs::msg::Image>(
"/out_image", 100, [&images] (sensor_msgs::msg::Image msg) {
"/out_image", 100, [&images](sensor_msgs::msg::Image msg) {
images.push_back(msg);
});

Expand Down Expand Up @@ -316,9 +317,9 @@ TEST(cognitive_module_test, startup_simple)

rclcpp::NodeOptions options;
options.arguments(
{"--ros-args", "-r", "__node:=cognitive_module_1", "--params-file", config_file});
{"--ros-args", "--params-file", config_file});

auto cm1 = cs4home_core::CognitiveModule::make_shared(options);
auto cm1 = cs4home_core::CognitiveModule::make_shared("cognitive_module_1", options);
ASSERT_EQ(std::string(cm1->get_name()), "cognitive_module_1");

auto params = cm1->list_parameters({}, 0);
Expand All @@ -331,7 +332,7 @@ TEST(cognitive_module_test, startup_simple)

std::vector<sensor_msgs::msg::Image> images;
auto sub = sub_node->create_subscription<sensor_msgs::msg::Image>(
"/detections", 100, [&images] (sensor_msgs::msg::Image msg) {
"/detections", 100, [&images](sensor_msgs::msg::Image msg) {
images.push_back(msg);
});

Expand Down
Loading