Skip to content

Commit

Permalink
Deprecate non-stamped twist
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Apr 4, 2024
1 parent 54e01f6 commit cb2471e
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 10 deletions.
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

0 comments on commit cb2471e

Please sign in to comment.