diff --git a/tricycle_controller/doc/userdoc.rst b/tricycle_controller/doc/userdoc.rst index 991627eca2..30973762fd 100644 --- a/tricycle_controller/doc/userdoc.rst +++ b/tricycle_controller/doc/userdoc.rst @@ -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 -------------- @@ -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 -------------- diff --git a/tricycle_controller/src/tricycle_controller.cpp b/tricycle_controller/src/tricycle_controller.cpp index 07be8c2aae..5586b87efc 100644 --- a/tricycle_controller/src/tricycle_controller.cpp +++ b/tricycle_controller/src/tricycle_controller.cpp @@ -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( DEFAULT_COMMAND_TOPIC, rclcpp::SystemDefaultsQoS(), [this](const std::shared_ptr msg) -> void diff --git a/tricycle_controller/src/tricycle_controller_parameter.yaml b/tricycle_controller/src/tricycle_controller_parameter.yaml index 68fc2202c2..951c159510 100644 --- a/tricycle_controller/src/tricycle_controller_parameter.yaml +++ b/tricycle_controller/src/tricycle_controller_parameter.yaml @@ -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 " diff --git a/tricycle_controller/test/config/test_tricycle_controller.yaml b/tricycle_controller/test/config/test_tricycle_controller.yaml index efecfe968f..4cef3ee131 100644 --- a/tricycle_controller/test/config/test_tricycle_controller.yaml +++ b/tricycle_controller/test/config/test_tricycle_controller.yaml @@ -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]