Skip to content

Commit

Permalink
Minor fixes for #93 (#143)
Browse files Browse the repository at this point in the history
  • Loading branch information
cwecht authored Aug 2, 2024
1 parent e60450d commit 7121cb1
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 9 deletions.
6 changes: 3 additions & 3 deletions include/message_filters/sync_policies/approximate_time.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,9 @@ struct ApproximateTime : public PolicyBase<Ms...>
, pivot_(NO_PIVOT)
, max_interval_duration_(rclcpp::Duration(std::numeric_limits<int32_t>::max(), 999999999))
, age_penalty_(0.1)
, has_dropped_messages_(9, false)
, inter_message_lower_bounds_(9, rclcpp::Duration(0, 0))
, warned_about_incorrect_bound_(9, false)
, has_dropped_messages_(N_MESSAGES, false)
, inter_message_lower_bounds_(N_MESSAGES, rclcpp::Duration(0, 0))
, warned_about_incorrect_bound_(N_MESSAGES, false)
{
// The synchronizer will tend to drop many messages with a queue size of 1.
// At least 2 is recommended.
Expand Down
6 changes: 3 additions & 3 deletions include/message_filters/sync_policies/latest_time.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,9 @@
// POSSIBILITY OF SUCH DAMAGE.

/**
* \brief Synchronizes up to 9 messages by their rates with upsampling via zero-order-hold.
* \brief Synchronizes up to N messages by their rates with upsampling via zero-order-hold.
*
* LatestTime policy synchronizes up to 9 incoming channels by the rates they are received.
* LatestTime policy synchronizes up to N incoming channels by the rates they are received.
* The callback with all the messages will be triggered whenever the fastest message is received.
* The slower messages will be repeated at the rate of the fastest message and will be updated
* whenever a new one is received. This is essentially an upsampling of slower messages using a
Expand Down Expand Up @@ -375,7 +375,7 @@ struct LatestTime : public PolicyBase<M...>

std::vector<RateConfig> rate_configs_;

const int NO_PIVOT{9};
const int NO_PIVOT{Super::N_MESSAGES};

rclcpp::Clock::SharedPtr ros_clock_{nullptr};
};
Expand Down
6 changes: 3 additions & 3 deletions include/message_filters/time_synchronizer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,10 +40,10 @@ namespace message_filters
{

/**
* \brief Synchronizes up to 9 messages by their timestamps.
* \brief Synchronizes up to N messages by their timestamps.
*
* TimeSynchronizer synchronizes up to 9 incoming channels by the timestamps contained in their messages' headers.
* TimeSynchronizer takes anywhere from 2 to 9 message types as template parameters, and passes them through to a
* TimeSynchronizer synchronizes up to N incoming channels by the timestamps contained in their messages' headers.
* TimeSynchronizer takes anywhere from 2 to N message types as template parameters, and passes them through to a
* callback which takes a shared pointer of each.
*
* The required queue size parameter when constructing the TimeSynchronizer tells it how many sets of messages it should
Expand Down

0 comments on commit 7121cb1

Please sign in to comment.