-
Notifications
You must be signed in to change notification settings - Fork 971
Fix deprecation warnings for upcoming ROS Galactic release #631
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
Changes from 2 commits
6b36efd
7055b82
ca9e807
afa37fa
774841b
3326e80
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change | ||||||
|---|---|---|---|---|---|---|---|---|
|
|
@@ -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_); | ||||||||
|
|
@@ -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))) { | ||||||||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @ayrton04 should this be 1ns, 1s, ...?
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Thanks, I meant to ask the same question.
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. If I understand the equivalent ROS 1 code, it is also subtracting 1 nanosecond: robot_localization/src/ros_filter.cpp Line 611 in a2da33b
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. So the PRs involved here are https://github.com/cra-ros-pkg/robot_localization/pull/266/files and https://github.com/cra-ros-pkg/robot_localization/pull/279/files The only reason we subtract any time at all is to ensure that we go to a measurement (presumably the first) that is before robot_localization/src/ros_filter.cpp Lines 3322 to 3323 in 3326e80
If I had to guess (I didn't dig too far), the measurement times were likely stored as doubles originally, and the
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. However, that change could be outside of scope for this. It was meant to be 1 nanosecond, yes. |
||||||||
| RF_DEBUG( | ||||||||
| "ERROR: history interval is too small to revert to time " << | ||||||||
| filter_utilities::toSec(first_measurement_time) << "\n"); | ||||||||
|
|
@@ -815,7 +815,7 @@ void RosFilter<T>::loadParams() | |||||||
| // Try to resolve tf_prefix | ||||||||
| std::string tf_prefix = ""; | ||||||||
| std::string tf_prefix_path = ""; | ||||||||
| this->declare_parameter("tf_prefix"); | ||||||||
| this->declare_parameter<std::string>("tf_prefix"); | ||||||||
ayrton04 marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||||||||
| if (this->get_parameter("tf_prefix", tf_prefix_path)) { | ||||||||
| // Append the tf prefix in a tf2-friendly manner | ||||||||
| filter_utilities::appendPrefix(tf_prefix, map_frame_id_); | ||||||||
|
|
@@ -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)); | ||||||||
jacobperron marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||||||||
|
|
||||||||
| // 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); | ||||||||
|
|
@@ -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 | ||||||||
|
|
@@ -883,7 +883,7 @@ void RosFilter<T>::loadParams() | |||||||
| control_timeout = this->declare_parameter("control_timeout", 0.0); | ||||||||
|
|
||||||||
| if (use_control_) { | ||||||||
| this->declare_parameter("control_config"); | ||||||||
| this->declare_parameter<std::vector<bool>>("control_config"); | ||||||||
| if (this->get_parameter("control_config", control_update_vector)) { | ||||||||
| if (control_update_vector.size() != TWIST_SIZE) { | ||||||||
| std::cerr << "Control configuration must be of size " << TWIST_SIZE << | ||||||||
|
|
@@ -899,7 +899,7 @@ void RosFilter<T>::loadParams() | |||||||
| use_control_ = false; | ||||||||
| } | ||||||||
|
|
||||||||
| this->declare_parameter("acceleration_limits"); | ||||||||
| this->declare_parameter<std::vector<double>>("acceleration_limits"); | ||||||||
| if (this->get_parameter("acceleration_limits", acceleration_limits)) { | ||||||||
| if (acceleration_limits.size() != TWIST_SIZE) { | ||||||||
| std::cerr << "Acceleration configuration must be of size " << TWIST_SIZE << | ||||||||
|
|
@@ -915,7 +915,7 @@ void RosFilter<T>::loadParams() | |||||||
| acceleration_limits.resize(TWIST_SIZE, 1.0); | ||||||||
| } | ||||||||
|
|
||||||||
| this->declare_parameter("acceleration_gains"); | ||||||||
| this->declare_parameter<std::vector<double>>("acceleration_gains"); | ||||||||
| if (this->get_parameter("acceleration_gains", acceleration_gains)) { | ||||||||
| const int size = acceleration_gains.size(); | ||||||||
| if (size != TWIST_SIZE) { | ||||||||
|
|
@@ -929,7 +929,7 @@ void RosFilter<T>::loadParams() | |||||||
| } | ||||||||
| } | ||||||||
|
|
||||||||
| this->declare_parameter("deceleration_limits"); | ||||||||
| this->declare_parameter<std::vector<double>>("deceleration_limits"); | ||||||||
| if (this->get_parameter("deceleration_limits", deceleration_limits)) { | ||||||||
| if (deceleration_limits.size() != TWIST_SIZE) { | ||||||||
| std::cerr << "Deceleration configuration must be of size " << TWIST_SIZE << | ||||||||
|
|
@@ -945,7 +945,7 @@ void RosFilter<T>::loadParams() | |||||||
| deceleration_limits = acceleration_limits; | ||||||||
| } | ||||||||
|
|
||||||||
| this->declare_parameter("deceleration_gains"); | ||||||||
| this->declare_parameter<std::vector<double>>("deceleration_gains"); | ||||||||
| if (this->get_parameter("deceleration_gains", deceleration_gains)) { | ||||||||
| const int size = deceleration_gains.size(); | ||||||||
| if (size != TWIST_SIZE) { | ||||||||
|
|
@@ -977,7 +977,7 @@ void RosFilter<T>::loadParams() | |||||||
| dynamic_process_noise_covariance); | ||||||||
|
|
||||||||
| std::vector<double> initial_state; | ||||||||
| this->declare_parameter("initial_state"); | ||||||||
| this->declare_parameter<std::vector<double>>("initial_state"); | ||||||||
| if (this->get_parameter("initial_state", initial_state)) { | ||||||||
| if (initial_state.size() != STATE_SIZE) { | ||||||||
| std::cerr << "Initial state must be of size " << STATE_SIZE << | ||||||||
|
|
@@ -1066,7 +1066,7 @@ void RosFilter<T>::loadParams() | |||||||
| ss << "odom" << topic_ind++; | ||||||||
| std::string odom_topic_name = ss.str(); | ||||||||
| std::string odom_topic; | ||||||||
| this->declare_parameter(odom_topic_name); | ||||||||
| this->declare_parameter<std::string>(odom_topic_name); | ||||||||
|
|
||||||||
| rclcpp::Parameter parameter; | ||||||||
| if (rclcpp::PARAMETER_NOT_SET != this->get_parameter(odom_topic_name, parameter)) { | ||||||||
|
|
@@ -1217,7 +1217,7 @@ void RosFilter<T>::loadParams() | |||||||
| ss << "pose" << topic_ind++; | ||||||||
| std::string pose_topic_name = ss.str(); | ||||||||
| std::string pose_topic; | ||||||||
| this->declare_parameter(pose_topic_name); | ||||||||
| this->declare_parameter<std::string>(pose_topic_name); | ||||||||
|
|
||||||||
| rclcpp::Parameter parameter; | ||||||||
| if (rclcpp::PARAMETER_NOT_SET != this->get_parameter(pose_topic_name, parameter)) { | ||||||||
|
|
@@ -1335,7 +1335,7 @@ void RosFilter<T>::loadParams() | |||||||
| ss << "twist" << topic_ind++; | ||||||||
| std::string twist_topic_name = ss.str(); | ||||||||
| std::string twist_topic; | ||||||||
| this->declare_parameter(twist_topic_name); | ||||||||
| this->declare_parameter<std::string>(twist_topic_name); | ||||||||
|
|
||||||||
| rclcpp::Parameter parameter; | ||||||||
| if (rclcpp::PARAMETER_NOT_SET != this->get_parameter(twist_topic_name, parameter)) { | ||||||||
|
|
@@ -1417,7 +1417,7 @@ void RosFilter<T>::loadParams() | |||||||
| ss << "imu" << topic_ind++; | ||||||||
| std::string imu_topic_name = ss.str(); | ||||||||
| std::string imu_topic; | ||||||||
| this->declare_parameter(imu_topic_name); | ||||||||
| this->declare_parameter<std::string>(imu_topic_name); | ||||||||
|
|
||||||||
| rclcpp::Parameter parameter; | ||||||||
| if (rclcpp::PARAMETER_NOT_SET != this->get_parameter(imu_topic_name, parameter)) { | ||||||||
|
|
@@ -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); | ||||||||
|
|
||||||||
|
|
@@ -1727,7 +1727,7 @@ void RosFilter<T>::loadParams() | |||||||
| process_noise_covariance.setZero(); | ||||||||
| std::vector<double> process_noise_covar_flat; | ||||||||
|
|
||||||||
| this->declare_parameter("process_noise_covariance"); | ||||||||
| this->declare_parameter<std::vector<double>>("process_noise_covariance"); | ||||||||
| if (this->get_parameter( | ||||||||
| "process_noise_covariance", | ||||||||
| process_noise_covar_flat)) | ||||||||
|
|
@@ -1754,7 +1754,7 @@ void RosFilter<T>::loadParams() | |||||||
| initial_estimate_error_covariance.setZero(); | ||||||||
| std::vector<double> estimate_error_covar_flat; | ||||||||
|
|
||||||||
| this->declare_parameter("initial_estimate_covariance"); | ||||||||
| this->declare_parameter<std::vector<double>>("initial_estimate_covariance"); | ||||||||
| if (this->get_parameter( | ||||||||
| "initial_estimate_covariance", | ||||||||
| estimate_error_covar_flat)) | ||||||||
|
|
||||||||
Uh oh!
There was an error while loading. Please reload this page.