Skip to content

Commit 55ac441

Browse files
committed
deprecated tf prefix flag
- log message added if tf_frame_prefix_enable is not set default - relevant info added to yaml description, migration and release notes
1 parent 0e25332 commit 55ac441

File tree

4 files changed

+22
-1
lines changed

4 files changed

+22
-1
lines changed

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -405,6 +405,17 @@ controller_interface::CallbackReturn DiffDriveController::on_configure(
405405
}
406406
});
407407

408+
// deprecation warning if tf_frame_prefix_enable set to non-default value
409+
const bool default_tf_frame_prefix_enable = true;
410+
if (params_.tf_frame_prefix_enable != default_tf_frame_prefix_enable)
411+
{
412+
RCLCPP_WARN(
413+
get_node()->get_logger(),
414+
"Parameter 'tf_frame_prefix_enable' is DEPRECATED and set to a non-default value (%s). "
415+
"Please migrate to 'tf_frame_prefix'.",
416+
params_.tf_frame_prefix_enable ? "true" : "false");
417+
}
418+
408419
// initialize odometry publisher and message
409420
odometry_publisher_ = get_node()->create_publisher<nav_msgs::msg::Odometry>(
410421
DEFAULT_ODOMETRY_TOPIC, rclcpp::SystemDefaultsQoS());

diff_drive_controller/src/diff_drive_controller_parameter.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ diff_drive_controller:
4949
tf_frame_prefix_enable: {
5050
type: bool,
5151
default_value: true,
52-
description: "Enables or disables appending tf_prefix to tf frame id's.",
52+
description: "Deprecated: this parameter will be removed in a future release. Use 'tf_frame_prefix' instead.",
5353
}
5454
tf_frame_prefix: {
5555
type: string,

doc/migration.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,3 +4,8 @@ Migration Guides: Kilted Kaiju to Lyrical Luth
44
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
55

66
This list summarizes important changes between Kilted Kaiju (previous) and Lyrical Luth (current) releases, where changes to user code might be necessary.
7+
8+
diff_drive_controller
9+
*****************************
10+
* Remove unused parameter ``tf_frame_prefix_enable``, use ``tf_frame_prefix`` instead. (`#1997 <https://github.com/ros-controls/ros2_controllers/pull/1997>`_).
11+
* Now any tilde ("~") character in ``tf_frame_prefix`` is substituted with node namespace. (`#1997 <https://github.com/ros-controls/ros2_controllers/pull/1997>`_).

doc/release_notes.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,3 +4,8 @@ Release Notes: Kilted Kaiju to Lyrical Luth
44
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
55

66
This list summarizes important changes between Kilted Kaiju (previous) and Lyrical Luth (current) releases.
7+
8+
diff_drive_controller
9+
*****************************
10+
* Remove unused parameter ``tf_frame_prefix_enable``, use ``tf_frame_prefix`` instead. (`#1997 <https://github.com/ros-controls/ros2_controllers/pull/1997>`_).
11+
* Now any tilde ("~") character in ``tf_frame_prefix`` is substituted with node namespace. (`#1997 <https://github.com/ros-controls/ros2_controllers/pull/1997>`_).

0 commit comments

Comments
 (0)