Skip to content

Commit

Permalink
Address review feedback
Browse files Browse the repository at this point in the history
* Remove unused interfaces
* Document LIFO order for invoking callbacks
* Add test cases to verify LIFO order for callbacks

Signed-off-by: Michael Jeronimo <michael.jeronimo@openrobotics.org>
  • Loading branch information
Michael Jeronimo committed Feb 11, 2021
1 parent 18e72cf commit e08612c
Show file tree
Hide file tree
Showing 2 changed files with 81 additions and 7 deletions.
9 changes: 4 additions & 5 deletions rclcpp/include/rclcpp/parameter_event_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,8 @@

#include "rclcpp/create_subscription.hpp"
#include "rclcpp/node_interfaces/get_node_base_interface.hpp"
#include "rclcpp/node_interfaces/get_node_logging_interface.hpp"
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/qos.hpp"
Expand Down Expand Up @@ -144,6 +142,9 @@ struct ParameterEventCallbackHandle
* };
* auto handle3 = param_handler->add_parameter_event_callback(cb3);
*
* For both parameter callbacks and parameter event callbacks, when multiple callbacks are added,
* the callbacks are invoked last-in, first-called order (LIFO).
*
* To remove a parameter event callback, use
*
* param_handler->remove_event_parameter_callback(handle);
Expand All @@ -163,7 +164,6 @@ class ParameterEventHandler
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)))
{
node_base_ = rclcpp::node_interfaces::get_node_base_interface(node);
node_logging_ = rclcpp::node_interfaces::get_node_logging_interface(node);
auto node_topics = rclcpp::node_interfaces::get_node_topics_interface(node);

event_subscription_ = rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
Expand Down Expand Up @@ -285,9 +285,8 @@ class ParameterEventHandler
// Utility function for resolving node path.
std::string resolve_path(const std::string & path);

// Node Interfaces used for base and logging.
// Node interface used for base functionality
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base_;
std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface> node_logging_;

// *INDENT-OFF* Uncrustify doesn't handle indented public/private labels
// Hash function for string pair required in std::unordered_map
Expand Down
79 changes: 77 additions & 2 deletions rclcpp/test/rclcpp/test_parameter_event_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <memory>
#include <string>
#include <thread>

#include "gtest/gtest.h"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -30,10 +32,15 @@ class TestParameterEventHandler : public rclcpp::ParameterEventHandler
event_callback(event);
}

size_t num_installed_handlers()
size_t num_event_callbacks()
{
return event_callbacks_.size();
}

size_t num_parameter_callbacks()
{
return parameter_callbacks_.size();
}
};

class TestNode : public ::testing::Test
Expand Down Expand Up @@ -166,6 +173,10 @@ TEST_F(TestNode, SameParameterDifferentNode)
param_handler->test_event(diff_node_int);
EXPECT_NE(int_param_node1, 1);
EXPECT_EQ(int_param_node2, 1);

param_handler->remove_parameter_callback(h1);
param_handler->remove_parameter_callback(h2);
EXPECT_EQ(param_handler->num_parameter_callbacks(), 0UL);
}

TEST_F(TestNode, GetParameterFromEvent)
Expand Down Expand Up @@ -353,5 +364,69 @@ TEST_F(TestNode, MultipleParameterCallbacks)

// All callbacks should have been removed
EXPECT_EQ(received_2, 0);
EXPECT_EQ(param_handler->num_installed_handlers(), 0UL);
EXPECT_EQ(param_handler->num_event_callbacks(), 0UL);
}

TEST_F(TestNode, LastInFirstCallForParameterCallbacks)
{
rclcpp::Time time_1;
rclcpp::Time time_2;

// The callbacks will log the current time for comparison purposes. Add a bit of a stall
// to ensure that the time noted in the back-to-back calls isn't the same
auto cb1 = [this, &time_1](const rclcpp::Parameter &) {
time_1 = node->now();
std::this_thread::sleep_for(std::chrono::milliseconds(10));
};
auto cb2 = [this, &time_2](const rclcpp::Parameter &) {
time_2 = node->now();
std::this_thread::sleep_for(std::chrono::milliseconds(10));
};

auto h1 = param_handler->add_parameter_callback("my_int", cb1);
auto h2 = param_handler->add_parameter_callback("my_int", cb2);

// Test multiple callbacks per parameter
param_handler->test_event(same_node_int);

// The most-recently install handler should be called first
EXPECT_EQ(time_2 < time_1, true);

param_handler->remove_parameter_callback(h1);
param_handler->remove_parameter_callback(h2);
EXPECT_EQ(param_handler->num_parameter_callbacks(), 0UL);
}

TEST_F(TestNode, LastInFirstCallForParameterEventCallbacks)
{
rclcpp::Time time_1;
rclcpp::Time time_2;

// The callbacks will log the current time for comparison purposes. Add a bit of a stall
// to ensure that the time noted in the back-to-back calls isn't the same
auto cb1 =
[this, &time_1](const rcl_interfaces::msg::ParameterEvent::SharedPtr &)
{
time_1 = node->now();
std::this_thread::sleep_for(std::chrono::milliseconds(10));
};
auto cb2 =
[this, &time_2](const rcl_interfaces::msg::ParameterEvent::SharedPtr &)
{
time_2 = node->now();
std::this_thread::sleep_for(std::chrono::milliseconds(10));
};

auto h1 = param_handler->add_parameter_event_callback(cb1);
auto h2 = param_handler->add_parameter_event_callback(cb2);

// Test multiple callbacks per parameter
param_handler->test_event(same_node_int);

// The most-recently install handler should be called first
EXPECT_EQ(time_2 < time_1, true);

param_handler->remove_parameter_event_callback(h1);
param_handler->remove_parameter_event_callback(h2);
EXPECT_EQ(param_handler->num_event_callbacks(), 0UL);
}

0 comments on commit e08612c

Please sign in to comment.