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
15 changes: 10 additions & 5 deletions control_toolbox/test/pid_ros_parameters_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -240,6 +240,9 @@ TEST(PidParametersTest, SetParametersTest)
{
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("pid_parameters_test");

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);

TestablePidROS pid(node, "", "", false);

const double P = 1.0;
Expand Down Expand Up @@ -295,8 +298,7 @@ TEST(PidParametersTest, SetParametersTest)
set_result = node->set_parameter(rclcpp::Parameter("activate_state_publisher", true)));
ASSERT_TRUE(set_result.successful);

// process callbacks
rclcpp::spin_some(node->get_node_base_interface());
executor.spin_some();

// check gains were set using the parameters
control_toolbox::Pid::Gains gains = pid.get_gains();
Expand All @@ -315,6 +317,9 @@ TEST(PidParametersTest, SetBadParametersTest)
{
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("pid_parameters_test");

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);

TestablePidROS pid(node, "", "", false);

const double P = 1.0;
Expand Down Expand Up @@ -370,7 +375,7 @@ TEST(PidParametersTest, SetBadParametersTest)
ASSERT_TRUE(set_result.successful);

// process callbacks
rclcpp::spin_some(node->get_node_base_interface());
executor.spin_some();

// check gains were NOT set using the parameters but the u_max and u_min
// were set to infinity as saturation is false
Expand All @@ -393,7 +398,7 @@ TEST(PidParametersTest, SetBadParametersTest)
ASSERT_TRUE(set_result.successful);

// process callbacks
rclcpp::spin_some(node->get_node_base_interface());
executor.spin_some();

// Setting good gains doesn't help, as the saturation is still false
gains = pid.get_gains();
Expand All @@ -412,7 +417,7 @@ TEST(PidParametersTest, SetBadParametersTest)
ASSERT_TRUE(set_result.successful);

// process callbacks
rclcpp::spin_some(node->get_node_base_interface());
executor.spin_some();

// check gains were NOT set using the parameters
control_toolbox::Pid::Gains updated_gains = pid.get_gains();
Expand Down
31 changes: 23 additions & 8 deletions control_toolbox/test/pid_ros_publisher_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@ TEST(PidPublisherTest, PublishTest)

auto node = std::make_shared<rclcpp::Node>("pid_publisher_test");

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);

control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "", true);

AntiWindupStrategy antiwindup_strat;
Expand Down Expand Up @@ -66,7 +69,7 @@ TEST(PidPublisherTest, PublishTest)
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
{
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
rclcpp::spin_some(node);
executor.spin_some();
std::this_thread::sleep_for(DELAY);
}

Expand All @@ -82,6 +85,9 @@ TEST(PidPublisherTest, PublishTest_start_deactivated)

auto node = std::make_shared<rclcpp::Node>("pid_publisher_test");

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);

control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "", false);

AntiWindupStrategy antiwindup_strat;
Expand Down Expand Up @@ -110,7 +116,7 @@ TEST(PidPublisherTest, PublishTest_start_deactivated)
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
{
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
rclcpp::spin_some(node);
executor.spin_some();
std::this_thread::sleep_for(DELAY);
}
ASSERT_FALSE(callback_called);
Expand All @@ -126,7 +132,7 @@ TEST(PidPublisherTest, PublishTest_start_deactivated)
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
{
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
rclcpp::spin_some(node);
executor.spin_some();
std::this_thread::sleep_for(DELAY);
}
ASSERT_TRUE(callback_called);
Expand All @@ -135,15 +141,15 @@ TEST(PidPublisherTest, PublishTest_start_deactivated)
ASSERT_NO_THROW(
set_result = node->set_parameter(rclcpp::Parameter("activate_state_publisher", false)));
ASSERT_TRUE(set_result.successful);
rclcpp::spin_some(node); // process callbacks to ensure that no further messages are received
executor.spin_some(); // process callbacks to ensure that no further messages are received
callback_called = false;
last_state_msg.reset();

// wait for callback
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
{
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
rclcpp::spin_some(node);
executor.spin_some();
std::this_thread::sleep_for(DELAY);
}
ASSERT_FALSE(callback_called);
Expand All @@ -157,6 +163,9 @@ TEST(PidPublisherTest, PublishTest_prefix)

auto node = std::make_shared<rclcpp::Node>("pid_publisher_test");

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);

// test with a prefix for the topic without trailing / (should be auto-added)
control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "global", true);

Expand Down Expand Up @@ -186,7 +195,7 @@ TEST(PidPublisherTest, PublishTest_prefix)
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
{
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
rclcpp::spin_some(node);
executor.spin_some();
std::this_thread::sleep_for(DELAY);
}

Expand All @@ -202,6 +211,9 @@ TEST(PidPublisherTest, PublishTest_local_prefix)

auto node = std::make_shared<rclcpp::Node>("pid_publisher_test");

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);

control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "~/local/", true);

AntiWindupStrategy antiwindup_strat;
Expand Down Expand Up @@ -230,7 +242,7 @@ TEST(PidPublisherTest, PublishTest_local_prefix)
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
{
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
rclcpp::spin_some(node);
executor.spin_some();
std::this_thread::sleep_for(DELAY);
}

Expand Down Expand Up @@ -302,6 +314,9 @@ TEST(PidPublisherTest, PublishTestLifecycle)

auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("pid_publisher_test");

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node->get_node_base_interface());

control_toolbox::PidROS pid_ros(node, "", "", true);

auto state_pub_lifecycle_ =
Expand Down Expand Up @@ -334,7 +349,7 @@ TEST(PidPublisherTest, PublishTestLifecycle)
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
{
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
rclcpp::spin_some(node->get_node_base_interface());
executor.spin_some();
std::this_thread::sleep_for(DELAY);
}
ASSERT_TRUE(callback_called);
Expand Down