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

Fix throttle duration #866

Merged
merged 2 commits into from
Mar 12, 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
4 changes: 2 additions & 2 deletions src/ros_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -348,7 +348,7 @@ void RosFilter<T>::controlStampedCallback(
filter_.setControl(latest_control_, msg->header.stamp);
} else {
RCLCPP_WARN_STREAM_THROTTLE(
get_logger(), *get_clock(), 5.0, "Commanded velocities "
get_logger(), *get_clock(), 5000, "Commanded velocities "
" must be given in the robot's body frame (" << base_link_frame_id_ <<
"). Message frame was " << msg->header.frame_id);
}
Expand Down Expand Up @@ -2221,7 +2221,7 @@ void RosFilter<T>::periodicUpdate()
RCLCPP_ERROR_STREAM_SKIPFIRST_THROTTLE(
get_logger(),
*get_clock(),
5.0,
5000,
"Could not obtain transform from " << odom_frame_id_ << "->" << base_link_frame_id_);
}
} else {
Expand Down
9 changes: 0 additions & 9 deletions src/ros_filter_utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,15 +49,6 @@
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2_ros/buffer.h"

#define THROTTLE(clock, duration, thing) do { \
static rclcpp::Time _last_output_time ## __LINE__(0, 0, (clock)->get_clock_type()); \
auto _now = (clock)->now(); \
if (_now - _last_output_time ## __LINE__ > (duration)) { \
_last_output_time ## __LINE__ = _now; \
thing; \
} \
} while (0)

std::ostream & operator<<(std::ostream & os, const tf2::Vector3 & vec)
{
os << "(" << std::setprecision(20) << vec.getX() << " " << vec.getY() << " " <<
Expand Down
22 changes: 5 additions & 17 deletions src/ros_robot_localization_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,15 +51,6 @@
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "yaml-cpp/yaml.h"

#define THROTTLE(clock, duration, thing) do { \
static rclcpp::Time _last_output_time ## __LINE__(0, 0, (clock)->get_clock_type()); \
auto _now = (clock)->now(); \
if (_now - _last_output_time ## __LINE__ > (duration)) { \
_last_output_time ## __LINE__ = _now; \
thing; \
} \
} while (0)

namespace robot_localization
{
FilterTypes::FilterType filterTypeFromString(
Expand Down Expand Up @@ -165,14 +156,11 @@ RosRobotLocalizationListener::RosRobotLocalizationListener(
// Wait until the base and world frames are set by the incoming messages
while (rclcpp::ok() && base_frame_id_.empty()) {
rclcpp::spin_some(node);
// TODO(ros2/rclcpp#879) RCLCPP_THROTTLE_INFO() when released
THROTTLE(
node->get_clock(), std::chrono::seconds(1),
RCLCPP_INFO(
node_logger_->get_logger(),
"Ros Robot Localization Listener: Waiting for incoming messages on "
"topics %s and %s",
odom_sub_.getTopic().c_str(), accel_sub_.getTopic().c_str()));
RCLCPP_INFO_THROTTLE(
node_logger_->get_logger(), *node->get_clock(), 1000,
"Ros Robot Localization Listener: Waiting for incoming messages on "
"topics %s and %s",
odom_sub_.getTopic().c_str(), accel_sub_.getTopic().c_str());
rclcpp::Rate(10).sleep();
}
}
Expand Down