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

Cleanups #134

Merged
merged 2 commits into from
Jul 8, 2024
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
19 changes: 4 additions & 15 deletions include/message_filters/message_event.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,19 +32,14 @@
#ifndef MESSAGE_FILTERS__MESSAGE_EVENT_H_
#define MESSAGE_FILTERS__MESSAGE_EVENT_H_

#include <type_traits>
#include <cassert>
#include <map>
#include <memory>
#include <string>
#include <type_traits>

#include <rclcpp/rclcpp.hpp>

#ifndef RCUTILS_ASSERT
// TODO(tfoote) remove this after it's implemented upstream
// https://github.com/ros2/rcutils/pull/112
#define RCUTILS_ASSERT assert
#endif

namespace message_filters
{
typedef std::map<std::string, std::string> M_string;
Expand All @@ -59,13 +54,7 @@ struct DefaultMessageCreator
}
};

/*
template<typename M>
ROS_DEPRECATED inline std::shared_ptr<M> defaultMessageCreateFunction()
{
return DefaultMessageCreator<M>()();
}
*/

/**
* \brief Event type for subscriptions, const message_filters::MessageEvent<M const> & can be used in your callback instead of const std::shared_ptr<M const>&
*
Expand Down Expand Up @@ -225,7 +214,7 @@ class MessageEvent
return message_copy_;
}

RCUTILS_ASSERT(create_);
assert(create_);
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
message_copy_ = create_();
*message_copy_ = *message_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ class ApproximateEpsilonTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7,
template<size_t i>
void add(const typename std::tuple_element<i, Events>::type & evt)
{
RCUTILS_ASSERT(parent_);
assert(parent_);

std::lock_guard<std::mutex> lock(mutex_);

Expand Down
50 changes: 19 additions & 31 deletions include/message_filters/sync_policies/approximate_time.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

#include <rcutils/logging_macros.h>

#include <cassert>
#include <deque>
#include <limits>
#include <string>
Expand All @@ -47,19 +48,6 @@
#include "message_filters/signal9.h"
#include "message_filters/synchronizer.h"


#ifndef RCUTILS_ASSERT
// TODO(tfoote) remove this after it's implemented upstream
// https://github.com/ros2/rcutils/pull/112
#define RCUTILS_ASSERT assert
#endif
#ifndef RCUTILS_BREAK
#include <cassert>
// TODO(tfoote) remove this after it's implemented upstream
// https://github.com/ros2/rcutils/pull/112
#define RCUTILS_BREAK std::abort
#endif

namespace message_filters
{
namespace sync_policies
Expand Down Expand Up @@ -122,7 +110,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
{
// The synchronizer will tend to drop many messages with a queue size of 1.
// At least 2 is recommended.
RCUTILS_ASSERT(queue_size_ > 0);
assert(queue_size_ > 0);
}

ApproximateTime(const ApproximateTime & e)
Expand Down Expand Up @@ -165,7 +153,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
}
std::deque<typename std::tuple_element<i, Events>::type> & deque = std::get<i>(deques_);
std::vector<typename std::tuple_element<i, Events>::type> & v = std::get<i>(past_);
RCUTILS_ASSERT(!deque.empty());
assert(!deque.empty());
const typename std::tuple_element<i, Messages>::type & msg = *(deque.back()).getMessage();
rclcpp::Time msg_time =
mt::TimeStamp<typename std::tuple_element<i, Messages>::type>::value(msg);
Expand Down Expand Up @@ -237,7 +225,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
recover<7>();
recover<8>();
// Drop the oldest message in the offending topic
RCUTILS_ASSERT(!deque.empty());
assert(!deque.empty());
deque.pop_front();
has_dropped_messages_[i] = true;
if (pivot_ != NO_PIVOT) {
Expand All @@ -254,23 +242,23 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
{
// For correctness we only need age_penalty > -1.0,
// but most likely a negative age_penalty is a mistake.
RCUTILS_ASSERT(age_penalty >= 0);
assert(age_penalty >= 0);
age_penalty_ = age_penalty;
}

void setInterMessageLowerBound(int i, rclcpp::Duration lower_bound)
{
// For correctness we only need age_penalty > -1.0,
// but most likely a negative age_penalty is a mistake.
RCUTILS_ASSERT(lower_bound >= rclcpp::Duration(0, 0));
assert(lower_bound >= rclcpp::Duration(0, 0));
inter_message_lower_bounds_[i] = lower_bound;
}

void setMaxIntervalDuration(rclcpp::Duration max_interval_duration)
{
// For correctness we only need age_penalty > -1.0,
// but most likely a negative age_penalty is a mistake.
RCUTILS_ASSERT(max_interval_duration >= rclcpp::Duration(0, 0));
assert(max_interval_duration >= rclcpp::Duration(0, 0));
max_interval_duration_ = max_interval_duration;
}

Expand All @@ -280,7 +268,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
void dequeDeleteFront()
{
std::deque<typename std::tuple_element<i, Events>::type> & deque = std::get<i>(deques_);
RCUTILS_ASSERT(!deque.empty());
assert(!deque.empty());
deque.pop_front();
if (deque.empty()) {
--num_non_empty_deques_;
Expand Down Expand Up @@ -319,7 +307,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
dequeDeleteFront<8>();
break;
default:
RCUTILS_BREAK();
std::abort();
}
}

Expand All @@ -329,7 +317,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
{
std::deque<typename std::tuple_element<i, Events>::type> & deque = std::get<i>(deques_);
std::vector<typename std::tuple_element<i, Events>::type> & vector = std::get<i>(past_);
RCUTILS_ASSERT(!deque.empty());
assert(!deque.empty());
vector.push_back(deque.front());
deque.pop_front();
if (deque.empty()) {
Expand Down Expand Up @@ -368,7 +356,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
dequeMoveFrontToPast<8>();
break;
default:
RCUTILS_BREAK();
std::abort();
}
}

Expand Down Expand Up @@ -422,7 +410,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>

std::vector<typename std::tuple_element<i, Events>::type> & v = std::get<i>(past_);
std::deque<typename std::tuple_element<i, Events>::type> & q = std::get<i>(deques_);
RCUTILS_ASSERT(num_messages <= v.size());
assert(num_messages <= v.size());
while (num_messages > 0) {
q.push_front(v.back());
v.pop_back();
Expand Down Expand Up @@ -469,7 +457,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
v.pop_back();
}

RCUTILS_ASSERT(!q.empty());
assert(!q.empty());

q.pop_front();
if (!q.empty()) {
Expand Down Expand Up @@ -597,12 +585,12 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
if (i >= RealTypeCount::value) {
return rclcpp::Time(0, 0); // Dummy return value
}
RCUTILS_ASSERT(pivot_ != NO_PIVOT);
assert(pivot_ != NO_PIVOT);

std::vector<typename std::tuple_element<i, Events>::type> & v = std::get<i>(past_);
std::deque<typename std::tuple_element<i, Events>::type> & q = std::get<i>(deques_);
if (q.empty()) {
RCUTILS_ASSERT(!v.empty()); // Because we have a candidate
assert(!v.empty()); // Because we have a candidate
rclcpp::Time last_msg_time =
mt::TimeStamp<typename std::tuple_element<i, Messages>::type>::value(
*(v.back()).getMessage());
Expand Down Expand Up @@ -715,7 +703,7 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
}
}
// INVARIANT: we have a candidate and pivot
RCUTILS_ASSERT(pivot_ != NO_PIVOT);
assert(pivot_ != NO_PIVOT);
rclcpp::Duration age_check = (end_time - candidate_end_) * (1 + age_penalty_);
if (start_index == pivot_) { // TODO(anyone): replace with start_time == pivot_time_
// We have exhausted all possible candidates for this pivot, we now can output the best one
Expand Down Expand Up @@ -764,14 +752,14 @@ struct ApproximateTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
recover<7>(num_virtual_moves[7]);
recover<8>(num_virtual_moves[8]);
(void)num_non_empty_deques_before_virtual_search; // unused variable warning stopper
RCUTILS_ASSERT(num_non_empty_deques_before_virtual_search == num_non_empty_deques_);
assert(num_non_empty_deques_before_virtual_search == num_non_empty_deques_);
break;
}
// Note: we cannot reach this point with start_index == pivot_ since in that case we would
// have start_time == pivot_time, in which case the two tests above are the negation
// of each other, so that one must be true. Therefore the while loop always terminates.
RCUTILS_ASSERT(start_index != pivot_);
RCUTILS_ASSERT(start_time < pivot_time_);
assert(start_index != pivot_);
assert(start_time < pivot_time_);
dequeMoveFrontToPast(start_index);
num_virtual_moves[start_index]++;
} // while(1)
Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/sync_policies/exact_time.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ struct ExactTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
template<int i>
void add(const typename std::tuple_element<i, Events>::type & evt)
{
RCUTILS_ASSERT(parent_);
assert(parent_);

namespace mt = message_filters::message_traits;

Expand Down
2 changes: 1 addition & 1 deletion include/message_filters/sync_policies/latest_time.h
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ struct LatestTime : public PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>
template<int i>
void add(const typename std::tuple_element<i, Events>::type & evt)
{
RCUTILS_ASSERT(parent_);
assert(parent_);

std::lock_guard<std::mutex> lock(data_mutex_);

Expand Down
3 changes: 1 addition & 2 deletions test/directed.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,11 @@
#
# wide.registerCallback(boost::bind(&PersonDataRecorder::wideCB, this, _1, _2, _3, _4));

import rclpy
import random
import unittest

from builtin_interfaces.msg import Time as TimeMsg
from message_filters import SimpleFilter, Subscriber, Cache, TimeSynchronizer
from message_filters import SimpleFilter, TimeSynchronizer


class MockHeader:
Expand Down
1 change: 0 additions & 1 deletion test/test_approxsync.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@
from message_filters import ApproximateTimeSynchronizer

import random
import rclpy
from rclpy.clock import ROSClock
from rclpy.duration import Duration
from rclpy.time import Time
Expand Down