Skip to content

Conversation

@KevinEppacher
Copy link

Basic Info

Info Value
Ticket(s) this addresses N/A
Primary OS tested on Ubuntu 22.04 LTS
Robotic platform tested on Simulated environment (Carter_ROS + IsaacSim 5.0.0 + Nav2 Humble)
Does this PR contain AI generated software? No
Was this PR description generated by AI software? No

Description of contribution in a few bullet points

  • Added a new optional field disable_collision_checks to the nav2_msgs/action/Spin goal message.
  • Updated the Spin behavior plugin to respect this flag and skip collision checking when set to true.
  • Enables developers to use the spin behavior safely in constrained or simulation-only contexts where collision checking is unnecessary (e.g., SLAM initialization or visual localization resets).
  • Default behavior remains unchanged – collision checks are still enabled unless explicitly disabled.

Description of documentation updates required from your changes

  • Update Spin behavior documentation to mention the new disable_collision_checks field.
  • Add the new field to default YAML examples under behavior_server configurations.
  • Note that this is an optional runtime flag for advanced users.

Description of how this change was tested

  • Built and run within ROS 2 Humble (see Repository SAGE)
  • Verified Spin behavior with and without disable_collision_checks: true flag using bt_navigator and custom launch configuration.
  • Confirmed normal behavior when omitted, and confirmed immediate spin without collision look-ahead when set to true.
bool Robot::spin(double yaw, double durationSec)
{
    if (!spinClient)
        spinClient = rclcpp_action::create_client<NavSpin>(node, "/spin");

    if (!spinClient->wait_for_action_server(1s))
    {
        RCLCPP_ERROR(node->get_logger(), "Spin action server not available");
        return false;
    }

    NavSpin::Goal goal;
    goal.target_yaw = yaw;
    goal.disable_collision_checks = true;
    goal.time_allowance = rclcpp::Duration::from_seconds(durationSec);

    spinDone = false;
    spinResult = rclcpp_action::ResultCode::UNKNOWN;

    auto options = rclcpp_action::Client<NavSpin>::SendGoalOptions();
    options.result_callback = [this](const GoalHandleSpin::WrappedResult& result)
    {
        spinDone = true;
        spinResult = result.code;
    };

    goalHandleFuture = spinClient->async_send_goal(goal, options);
    this->halted = false;
    return true;
}

Future work that may be required in bullet points

  • Add automated unit tests to confirm correct disabling of collision simulation.

For Maintainers

  • Check that new parameter is documented on docs.nav2.org
  • Add to migration and tuning guides if applicable
  • Confirm Doxygen and test coverage
  • Consider backport tag backport-humble

@mergify
Copy link
Contributor

mergify bot commented Oct 22, 2025

@KevinEppacher, all pull requests must be targeted towards the main development branch.
Once merged into main, it is possible to backport to @humble, but it must be in main
to have these changes reflected into new distributions.

#goal definition
float32 target_yaw
builtin_interfaces/Duration time_allowance
bool disable_collision_checks
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This cannot be backported. We cannot change message definitions unfortunately in released distributions. That breaks any and all existing users and MD5 hashes

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

[Humble] Spin behavior lacks disable_collision_checks flag (feature missing from newer Nav2)

2 participants