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
8 changes: 6 additions & 2 deletions include/message_filters/time_sequencer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ class TimeSequencer : public SimpleFilter<M>
, update_rate_(update_rate)
, queue_size_(queue_size)
, node_(node)
, last_time_ (0, 0, RCL_ROS_TIME)
{
init();
connectInput(f);
Expand All @@ -118,6 +119,7 @@ class TimeSequencer : public SimpleFilter<M>
, update_rate_(update_rate)
, queue_size_(queue_size)
, node_(node)
, last_time_ (0, 0, RCL_ROS_TIME)
{
init();
}
Expand Down Expand Up @@ -199,7 +201,7 @@ class TimeSequencer : public SimpleFilter<M>
while (!messages_.empty()) {
const EventType & e = *messages_.begin();
rclcpp::Time stamp = mt::TimeStamp<M>::value(*e.getMessage());
if ((stamp + delay_) <= rclcpp::Clock().now()) {
if ((stamp + delay_) <= node_->get_clock()->now()) {
last_time_ = stamp;
to_call.push_back(e);
messages_.erase(messages_.begin());
Expand All @@ -220,7 +222,9 @@ class TimeSequencer : public SimpleFilter<M>

void init()
{
update_timer_ = node_->create_wall_timer(
update_timer_ = rclcpp::create_timer(
node_,
node_->get_clock(),
std::chrono::nanoseconds(update_rate_.nanoseconds()), [this]() {
dispatch();
});
Expand Down
2 changes: 1 addition & 1 deletion test/test_fuzz.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ TEST(TimeSequencer, fuzz_sequencer)
10, node);
Helper h;
seq.registerCallback(std::bind(&Helper::cb, &h, std::placeholders::_1));
rclcpp::Clock ros_clock;
rclcpp::Clock ros_clock(RCL_ROS_TIME);
auto start = ros_clock.now();
auto msg = std::make_shared<Msg>();
while ((ros_clock.now() - start) < rclcpp::Duration(5, 0)) {
Expand Down
6 changes: 3 additions & 3 deletions test/time_sequencer_unittest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ struct TimeStamp<Msg>
{
static rclcpp::Time value(const Msg & m)
{
return m.header.stamp;
return rclcpp::Time(m.header.stamp, RCL_ROS_TIME);
}
};
} // namespace message_traits
Expand Down Expand Up @@ -86,7 +86,7 @@ TEST(TimeSequencer, simple)
Helper h;
seq.registerCallback(std::bind(&Helper::cb, &h, std::placeholders::_1));
MsgPtr msg(std::make_shared<Msg>());
msg->header.stamp = rclcpp::Clock().now();
msg->header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
seq.add(msg);

rclcpp::Rate(10).sleep();
Expand Down Expand Up @@ -137,7 +137,7 @@ TEST(TimeSequencer, eventInEventOut)
seq2.registerCallback(&EventHelper::cb, &h);

message_filters::MessageEvent<Msg const> evt(std::make_shared<Msg const>(),
rclcpp::Clock().now());
rclcpp::Clock(RCL_ROS_TIME).now());
seq.add(evt);

while (!h.event_.getMessage()) {
Expand Down