diff --git a/configuration/packages/collision_monitor/configuring-collision-monitor-node.rst b/configuration/packages/collision_monitor/configuring-collision-monitor-node.rst index b2e55eb6a..0501bca14 100644 --- a/configuration/packages/collision_monitor/configuring-collision-monitor-node.rst +++ b/configuration/packages/collision_monitor/configuring-collision-monitor-node.rst @@ -200,12 +200,13 @@ Parameters ============== ============================= Type Default -------------- ----------------------------- - bool false + bool true ============== ============================= Description Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data. True uses TwistStamped, false uses Twist. + Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default. Polygons parameters =================== @@ -608,7 +609,7 @@ Here is an example of configuration YAML for the Collision Monitor. source_timeout: 5.0 base_shift_correction: True stop_pub_timeout: 2.0 - enable_stamped_cmd_vel: False + enable_stamped_cmd_vel: True # False for Jazzy or older use_realtime_priority: false polygons: ["PolygonStop", "PolygonSlow", "FootprintApproach"] PolygonStop: diff --git a/configuration/packages/configuring-behavior-server.rst b/configuration/packages/configuring-behavior-server.rst index 80cac712a..1e4af7526 100644 --- a/configuration/packages/configuring-behavior-server.rst +++ b/configuration/packages/configuring-behavior-server.rst @@ -233,12 +233,13 @@ Spin distance is given from the action request ============== ============================= Type Default -------------- ----------------------------- - bool false + bool true ============== ============================= Description Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data. True uses TwistStamped, false uses Twist. + Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default. BackUp Behavior Parameters @@ -262,12 +263,13 @@ Backup distance, speed and time_allowance is given from the action request. ============== ============================= Type Default -------------- ----------------------------- - bool false + bool true ============== ============================= Description Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data. True uses TwistStamped, false uses Twist. + Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default. DriveOnHeading Behavior Parameters ********************************** @@ -290,12 +292,13 @@ DriveOnHeading distance, speed and time_allowance is given from the action reque ============== ============================= Type Default -------------- ----------------------------- - bool false + bool true ============== ============================= Description Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data. True uses TwistStamped, false uses Twist. + Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default. :bond_heartbeat_period: @@ -351,12 +354,13 @@ AssistedTeleop time_allowance is given in the action request ============== ============================= Type Default -------------- ----------------------------- - bool false + bool true ============== ============================= Description Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data. True uses TwistStamped, false uses Twist. + Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default. Example ******* @@ -388,4 +392,4 @@ Example max_rotational_vel: 1.0 min_rotational_vel: 0.4 rotational_acc_lim: 3.2 - enable_stamped_cmd_vel: false + enable_stamped_cmd_vel: true # default false in Jazzy or older diff --git a/configuration/packages/configuring-controller-server.rst b/configuration/packages/configuring-controller-server.rst index f3f0b780e..68ae28fc6 100644 --- a/configuration/packages/configuring-controller-server.rst +++ b/configuration/packages/configuring-controller-server.rst @@ -210,12 +210,13 @@ Parameters ============== ============================= Type Default -------------- ----------------------------- - bool false + bool true ============== ============================= Description Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data. True uses TwistStamped, false uses Twist. + Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default. :bond_heartbeat_period: diff --git a/configuration/packages/configuring-loopback-sim.rst b/configuration/packages/configuring-loopback-sim.rst index ab254a0e9..c217111cf 100644 --- a/configuration/packages/configuring-loopback-sim.rst +++ b/configuration/packages/configuring-loopback-sim.rst @@ -74,11 +74,12 @@ Parameters ============== ============== Type Default -------------- -------------- - string false + string True ============== ============== Description - Whether cmd_vel is stamped or unstamped (i.e. Twist or TwistStamped) + Whether cmd_vel is stamped or unstamped (i.e. Twist or TwistStamped). + Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default. :scan_publish_dur: diff --git a/configuration/packages/configuring-velocity-smoother.rst b/configuration/packages/configuring-velocity-smoother.rst index 36a9ab3aa..26a9fc3da 100644 --- a/configuration/packages/configuring-velocity-smoother.rst +++ b/configuration/packages/configuring-velocity-smoother.rst @@ -153,12 +153,13 @@ Velocity Smoother Parameters ============== ============================= Type Default -------------- ----------------------------- - bool false + bool true ============== ============================= Description Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data. True uses TwistStamped, false uses Twist. + Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default. :bond_heartbeat_period: diff --git a/migration/Jazzy.rst b/migration/Jazzy.rst index b123fefcc..f645c84ee 100644 --- a/migration/Jazzy.rst +++ b/migration/Jazzy.rst @@ -5,6 +5,20 @@ Jazzy to K-Turtle Moving from ROS 2 Jazzy to K-Turtle, a number of stability improvements were added that we will not specifically address here. +TwistStamped Default CmdVel Change +********************************** + +In Kilted and newer, the default ``cmd_vel`` topic for all ``Twist`` publishers and subscriptions is changed to ``TwistStamped`` in order to enable a broader range of applications. +it also allows for rejection of stale velocity messages, which can be useful in some applications. +Your robot should now subscribe to a ``TwistStamped`` message instead of a ``Twist`` message & update your simulation appropriately. +The topic names are the same. + +However, this can be disabled by setting ``enable_twist_stamped`` to ``false`` in the ``nav2_params.yaml`` file for all nodes that involve Twist subscriptions or publications. +See the configuration guide for more information on how to configure this parameter for each node. + +An example simulation migration using Gazebo can be seen in the `following pull request for the Turtlebot 3 and 4 `_. + + New Nav2 Loopback Simulator *************************** diff --git a/tutorials/docs/using_collision_monitor.rst b/tutorials/docs/using_collision_monitor.rst index 7b54e4570..5b354b0a5 100644 --- a/tutorials/docs/using_collision_monitor.rst +++ b/tutorials/docs/using_collision_monitor.rst @@ -87,7 +87,7 @@ The whole ``nav2_collision_monitor/params/collision_monitor_params.yaml`` file i transform_tolerance: 0.5 source_timeout: 5.0 stop_pub_timeout: 2.0 - enable_stamped_cmd_vel: False + enable_stamped_cmd_vel: True # False for Jazzy or older by default polygons: ["PolygonStop", "PolygonSlow"] PolygonStop: type: "polygon"