Skip to content

Commit

Permalink
Fix deprecation warnings when constructing rclcpp::Duration objects
Browse files Browse the repository at this point in the history
If we are constructing from nanoseconds we must be explicit about the units.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Mar 17, 2021
1 parent 79162b2 commit 6b36efd
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
2 changes: 1 addition & 1 deletion src/robot_localization_estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ void RobotLocalizationEstimator::extrapolate(
rclcpp::Time time_stamp = rclcpp::Time(
boundary_state.time_stamp *
1000000000);
rclcpp::Duration delta_duration = rclcpp::Duration(delta * 1000000000);
rclcpp::Duration delta_duration = rclcpp::Duration::from_nanoseconds(delta * 1000000000);
filter_->predict(time_stamp, delta_duration);

state_at_req_time.time_stamp = requested_time;
Expand Down
18 changes: 9 additions & 9 deletions src/ros_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,12 +72,12 @@ RosFilter<T>::RosFilter(const rclcpp::NodeOptions & options)
static_diag_error_level_(diagnostic_msgs::msg::DiagnosticStatus::OK),
frequency_(30.0),
gravitational_acceleration_(9.80665),
history_length_(0),
history_length_(0ns),
latest_control_(),
last_set_pose_time_(0, 0, RCL_ROS_TIME),
latest_control_time_(0, 0, RCL_ROS_TIME),
tf_timeout_(0),
tf_time_offset_(0)
tf_timeout_(0ns),
tf_time_offset_(0ns)
{
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf_buffer_);
Expand Down Expand Up @@ -604,7 +604,7 @@ void RosFilter<T>::integrateMeasurements(const rclcpp::Time & current_time)
const std::string first_measurement_topic =
first_measurement->topic_name_;
// revertTo may invalidate first_measurement
if (!revertTo(first_measurement_time - rclcpp::Duration(1))) {
if (!revertTo(first_measurement_time - rclcpp::Duration(1ns))) {
RF_DEBUG(
"ERROR: history interval is too small to revert to time " <<
filter_utilities::toSec(first_measurement_time) << "\n");
Expand Down Expand Up @@ -834,18 +834,18 @@ void RosFilter<T>::loadParams()
// Transform future dating
double offset_tmp = this->declare_parameter("transform_time_offset", 0.0);
tf_time_offset_ =
rclcpp::Duration(filter_utilities::secToNanosec(offset_tmp));
rclcpp::Duration::from_nanoseconds(filter_utilities::secToNanosec(offset_tmp));

// Transform timeout
double timeout_tmp = this->declare_parameter("transform_timeout", 0.0);
tf_timeout_ = rclcpp::Duration(filter_utilities::secToNanosec(timeout_tmp));
tf_timeout_ = rclcpp::Duration::from_nanoseconds(filter_utilities::secToNanosec(timeout_tmp));

// Update frequency and sensor timeout
frequency_ = this->declare_parameter("frequency", 30.0);

double sensor_timeout = this->declare_parameter("sensor_timeout", 1.0 / frequency_);
filter_.setSensorTimeout(
rclcpp::Duration(filter_utilities::secToNanosec(sensor_timeout)));
rclcpp::Duration::from_nanoseconds(filter_utilities::secToNanosec(sensor_timeout)));

// Determine if we're in 2D mode
two_d_mode_ = this->declare_parameter("two_d_mode", false);
Expand All @@ -865,7 +865,7 @@ void RosFilter<T>::loadParams()
" specified. Absolute value will be assumed.";
}

history_length_ = rclcpp::Duration(
history_length_ = rclcpp::Duration::from_nanoseconds(
filter_utilities::secToNanosec(std::abs(history_length_double)));

// Whether we reset filter on jump back in time
Expand Down Expand Up @@ -1663,7 +1663,7 @@ void RosFilter<T>::loadParams()

filter_.setControlParams(
control_update_vector,
rclcpp::Duration(filter_utilities::secToNanosec(control_timeout)),
rclcpp::Duration::from_nanoseconds(filter_utilities::secToNanosec(control_timeout)),
acceleration_limits, acceleration_gains, deceleration_limits,
deceleration_gains);

Expand Down

0 comments on commit 6b36efd

Please sign in to comment.