@@ -338,6 +338,7 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi
338338 return ;
339339 }
340340
341+ std::vector<std::tuple<uint64_t , tf2::TimePoint, std::string>> wait_params;
341342 // iterate through the target frames and add requests for each of them
342343 MessageInfo info;
343344 info.handles .reserve (expected_success_count_);
@@ -353,63 +354,17 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi
353354 V_string::iterator end = target_frames_copy.end ();
354355 for (; it != end; ++it) {
355356 const std::string & target_frame = *it;
356- auto future = buffer_.waitForTransform (
357- target_frame,
358- frame_id,
359- tf2::timeFromSec (stamp.seconds ()),
360- buffer_timeout_,
361- std::bind (&MessageFilter::transformReadyCallback, this , std::placeholders::_1, next_handle_index_));
362-
363- try {
364- const auto status = future.wait_for (std::chrono::seconds (0 ));
365- if (status == std::future_status::ready) {
366- future.get ();
367- // Transform is available
368- ++info.success_count ;
369- }
370- else {
371- info.handles .push_back (next_handle_index_++);
372- }
373- }
374- catch (const std::exception & e) {
375- TF2_ROS_MESSAGEFILTER_WARN (" Message dropped because: %s" , e.what ());
376- messageDropped (evt, filter_failure_reasons::OutTheBack);
377- return ;
378- }
357+ wait_params.emplace_back (next_handle_index_, tf2::timeFromSec (stamp.seconds ()), target_frame);
358+ info.handles .push_back (next_handle_index_++);
379359
380360 if (time_tolerance_.nanoseconds ()) {
381- future = buffer_.waitForTransform (
382- target_frame,
383- frame_id,
384- tf2::timeFromSec ((stamp + time_tolerance_).seconds ()),
385- buffer_timeout_,
386- std::bind (&MessageFilter::transformReadyCallback, this , std::placeholders::_1, next_handle_index_));
387- try {
388- const auto status = future.wait_for (std::chrono::seconds (0 ));
389- if (status == std::future_status::ready) {
390- future.get ();
391- // Transform is available
392- ++info.success_count ;
393- }
394- else {
395- info.handles .push_back (next_handle_index_++);
396- }
397- }
398- catch (const std::exception & e) {
399- TF2_ROS_MESSAGEFILTER_WARN (" Message dropped because: %s" , e.what ());
400- messageDropped (evt, filter_failure_reasons::OutTheBack);
401- return ;
402- }
361+ wait_params.emplace_back (next_handle_index_, tf2::timeFromSec ((stamp + time_tolerance_).seconds ()), target_frame);
362+ info.handles .push_back (next_handle_index_++);
403363 }
404364 }
405365 }
406366
407-
408- // We can transform already
409- if (info.success_count == expected_success_count_) {
410- messageReady (evt);
411- } else {
412-
367+ {
413368 // Keep a lock on the messages
414369 std::unique_lock<std::mutex> unique_lock (messages_mutex_);
415370
@@ -439,6 +394,18 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi
439394 TF2_ROS_MESSAGEFILTER_DEBUG (" Added message in frame %s at time %.3f, count now %d" ,
440395 frame_id.c_str (), stamp.seconds (), message_count_);
441396 ++incoming_message_count_;
397+
398+ for (const auto & param : wait_params) {
399+ const auto & handle = std::get<0 >(param);
400+ const auto & stamp = std::get<1 >(param);
401+ const auto & target_frame = std::get<2 >(param);
402+ buffer_.waitForTransform (
403+ target_frame,
404+ frame_id,
405+ stamp,
406+ buffer_timeout_,
407+ std::bind (&MessageFilter::transformReadyCallback, this , std::placeholders::_1, handle));
408+ }
442409 }
443410
444411 /* *
0 commit comments