Skip to content

Commit

Permalink
Override reset function
Browse files Browse the repository at this point in the history
  • Loading branch information
RBT22 committed Jan 31, 2025
1 parent 6a22187 commit 3e408b9
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,11 @@ class RotationShimController : public nav2_core::Controller
*/
void setSpeedLimit(const double & speed_limit, const bool & percentage) override;

/**
* @brief Reset the state of the controller
*/
void reset() override;

protected:
/**
* @brief Finds the point on the path that is roughly the sampling
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -388,6 +388,12 @@ void RotationShimController::setSpeedLimit(const double & speed_limit, const boo
primary_controller_->setSpeedLimit(speed_limit, percentage);
}

void RotationShimController::reset()
{
last_angular_vel_ = std::numeric_limits<double>::max();
primary_controller_->reset();
}

rcl_interfaces::msg::SetParametersResult
RotationShimController::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
{
Expand Down

0 comments on commit 3e408b9

Please sign in to comment.