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

Deprecate non-stamped twist for tricycle_controller and steering_controllers #1093

Merged
merged 3 commits into from
May 8, 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
2 changes: 1 addition & 1 deletion diff_drive_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ Subscribers
,,,,,,,,,,,,

~/cmd_vel [geometry_msgs/msg/TwistStamped]
Velocity command for the controller, if ``use_stamped_vel=true``. The controller extracts the x component of the linear velocity and the z component of the angular velocity. Velocities on other components are ignored.
Velocity command for the controller. The controller extracts the x component of the linear velocity and the z component of the angular velocity. Velocities on other components are ignored.


Publishers
Expand Down
5 changes: 1 addition & 4 deletions steering_controllers_library/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ Nomenclature used for the controller is used from `wikipedia <https://en.wikiped
Execution logic of the controller
----------------------------------

The controller uses velocity input, i.e., stamped or unstamped Twist messages where linear ``x`` and angular ``z`` components are used.
The controller uses velocity input, i.e., stamped Twist messages where linear ``x`` and angular ``z`` components are used.
Angular component under
Values in other components are ignored.
In the chain mode the controller provides two reference interfaces, one for linear velocity and one for steering angle position.
Expand Down Expand Up @@ -74,9 +74,6 @@ Subscribers
Used when controller is not in chained mode (``in_chained_mode == false``).

- <controller_name>/reference [geometry_msgs/msg/TwistStamped]
If parameter ``use_stamped_vel`` is ``true``.
- <controller_name>/reference_unstamped [geometry_msgs/msg/Twist]
If parameter ``use_stamped_vel`` is ``false``.

Publishers
,,,,,,,,,,,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,9 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure(
ref_timeout_ = rclcpp::Duration::from_seconds(params_.reference_timeout);
if (params_.use_stamped_vel)
{
RCLCPP_WARN(
get_node()->get_logger(),
"[Deprecated] Using geometry_msgs::msg::Twist instead of TwistStamped is deprecated.");
ref_subscriber_twist_ = get_node()->create_subscription<ControllerTwistReferenceMsg>(
"~/reference", subscribers_qos,
std::bind(&SteeringControllersLibrary::reference_callback, this, std::placeholders::_1));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ steering_controllers_library:
use_stamped_vel: {
type: bool,
default_value: false,
description: "Choice of vel type, if use_stamped_vel is false then ``geometry_msgs::msg::Twist`` is taken as vel msg type, if
description: "(Deprecated) Choice of vel type, if use_stamped_vel is false then ``geometry_msgs::msg::Twist`` is taken as vel msg type, if
use_stamped_vel is true then ``geometry_msgs::msg::TwistStamped`` is taken as vel msg type",
read_only: false,
}
18 changes: 10 additions & 8 deletions tricycle_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,6 @@ Controller for mobile robots with a single double-actuated wheel, including trac
Input for control are robot base_link twist commands which are translated to traction and steering
commands for the tricycle drive base. Odometry is computed from hardware feedback and published.

Velocity commands
-----------------

The controller works with a velocity twist from which it extracts
the x component of the linear velocity and the z component of the angular velocity.
Velocities on other components are ignored.


Other features
--------------

Expand All @@ -26,6 +18,16 @@ Other features
Velocity, acceleration and jerk limits
Automatic stop after command timeout

ROS 2 Interfaces
------------------------

Subscribers
,,,,,,,,,,,,

~/cmd_vel [geometry_msgs/msg/TwistStamped]
Velocity command for the controller. The controller extracts the x component of the linear velocity and the z component of the angular velocity. Velocities on other components are ignored.


Parameters
--------------

Expand Down
3 changes: 3 additions & 0 deletions tricycle_controller/src/tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -316,6 +316,9 @@ CallbackReturn TricycleController::on_configure(const rclcpp_lifecycle::State &
}
else
{
RCLCPP_WARN(
get_node()->get_logger(),
"[Deprecated] Using geometry_msgs::msg::Twist instead of TwistStamped is deprecated.");
velocity_command_unstamped_subscriber_ = get_node()->create_subscription<Twist>(
DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS(),
[this](const std::shared_ptr<Twist> msg) -> void
Expand Down
2 changes: 1 addition & 1 deletion tricycle_controller/src/tricycle_controller_parameter.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ tricycle_controller:
use_stamped_vel: {
type: bool,
default_value: true,
description: "Use stamp from input velocity message to calculate how old the command actually is.",
description: "(deprecated) Use stamp from input velocity message to calculate how old the command actually is.",
}
traction:
# "The positive limit will be applied to both directions. Setting different limits for positive "
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@ test_tricycle_controller:
steering_joint_name: steering_joint
wheel_radius: 0.125
wheelbase: 1.252
use_stamped_vel: false
enable_odom_tf: false
use_sim_time: false
pose_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
Expand Down
Loading