Skip to content

Commit

Permalink
Fixes after merging Signed-off-by: Jakub Chudziński <[email protected]>
Browse files Browse the repository at this point in the history
Signed-off-by: Jakubach <[email protected]>
  • Loading branch information
Jakubach committed Nov 22, 2024
1 parent 932a318 commit 40a2b0f
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 13 deletions.
24 changes: 12 additions & 12 deletions nav2_docking/opennav_docking/include/opennav_docking/controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,18 @@ class Controller
const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking,
bool backward = false);

/**
* @brief Perform a command for in-place rotation.
* @param angular_distance_to_heading Angular distance to goal
* @param current_velocity Current angular velocity
* @param dt Control loop duration [s]
* @returns TwistStamped command.
*/
geometry_msgs::msg::Twist computeRotateToHeadingCommand(
const double & angular_distance_to_heading,
const geometry_msgs::msg::Twist & current_velocity,
const double & dt);

protected:
/**
* @brief Check if a trajectory is collision free.
Expand Down Expand Up @@ -103,18 +115,6 @@ class Controller
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
std::mutex dynamic_params_lock_;

/**
* @brief Perform a command for in-place rotation.
* @param angular_distance_to_heading Angular distance to goal
* @param current_velocity Current angular velocity
* @param dt Control loop duration [s]
* @returns TwistStamped command.
*/
geometry_msgs::msg::Twist computeRotateToHeadingCommand(
const double & angular_distance_to_heading,
const geometry_msgs::msg::Twist & current_velocity,
const double & dt);

protected:
rclcpp::Logger logger_{rclcpp::get_logger("Controller")};
rclcpp::Clock::SharedPtr clock_;
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/opennav_docking/src/docking_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -783,7 +783,7 @@ DockingServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> paramete
undock_linear_tolerance_ = parameter.as_double();
} else if (name == "undock_angular_tolerance") {
undock_angular_tolerance_ = parameter.as_double();
else if (name == "backward_rotation_tolerance") {
} else if (name == "backward_rotation_tolerance") {
backward_rotation_tolerance_ = parameter.as_double();
}
} else if (type == ParameterType::PARAMETER_STRING) {
Expand Down

0 comments on commit 40a2b0f

Please sign in to comment.