Skip to content

Commit 7d62a43

Browse files
committed
Initial rotation taken from rotation shim controller
1 parent 4855925 commit 7d62a43

File tree

4 files changed

+51
-28
lines changed

4 files changed

+51
-28
lines changed

nav2_docking/opennav_docking/include/opennav_docking/controller.hpp

+11-5
Original file line numberDiff line numberDiff line change
@@ -60,17 +60,23 @@ class Controller
6060
std::mutex dynamic_params_lock_;
6161

6262
/**
63-
* @brief Perform a rotation about an angle.
64-
* @param angle_to_target Rotation angle <-2*pi;2*pi>.
65-
* @returns Twist command.
63+
* @brief Perform a command for in-place rotation.
64+
* @param angular_distance_to_heading Angular distance to goal
65+
* @param current_velocity Current angular velocity
66+
* @param dt Control loop duration [s]
67+
* @returns TwistStamped command.
6668
*/
67-
geometry_msgs::msg::Twist rotateToTarget(const double & angle_to_target);
69+
geometry_msgs::msg::Twist computeRotateToHeadingCommand(
70+
const double & angular_distance_to_heading,
71+
const geometry_msgs::msg::Twist & current_velocity,
72+
const double & dt);
6873

6974
protected:
7075
std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
7176

7277
double k_phi_, k_delta_, beta_, lambda_;
73-
double slowdown_radius_, v_linear_min_, v_linear_max_, v_angular_max_, v_angular_min_;
78+
double slowdown_radius_, v_linear_min_, v_linear_max_, v_angular_max_;
79+
double rotate_to_heading_angular_vel_, rotate_to_heading_max_angular_accel_;
7480
};
7581

7682
} // namespace opennav_docking

nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@
3333
#include "opennav_docking/navigator.hpp"
3434
#include "opennav_docking_core/charging_dock.hpp"
3535
#include "tf2_ros/transform_listener.h"
36+
#include "nav_2d_utils/odom_subscriber.hpp"
3637

3738
namespace opennav_docking
3839
{
@@ -251,11 +252,14 @@ class DockingServer : public nav2_util::LifecycleNode
251252
double dock_prestaging_tolerance_;
252253
// Enable aproaching a docking station only with initial detection without updates
253254
bool backward_blind_;
255+
// Angle in which robot can stop initial rotation
256+
double backward_rotation_tolerance_;
254257

255258
// This is a class member so it can be accessed in publish feedback
256259
rclcpp::Time action_start_time_;
257260

258261
std::unique_ptr<nav2_util::TwistPublisher> vel_publisher_;
262+
std::unique_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
259263
std::unique_ptr<DockingActionServer> docking_action_server_;
260264
std::unique_ptr<UndockingActionServer> undocking_action_server_;
261265

nav2_docking/opennav_docking/src/controller.cpp

+12-16
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,6 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
4848
node->get_parameter("controller.lambda", lambda_);
4949
node->get_parameter("controller.v_linear_min", v_linear_min_);
5050
node->get_parameter("controller.v_linear_max", v_linear_max_);
51-
node->get_parameter("controller.v_angular_min", v_angular_min_);
5251
node->get_parameter("controller.v_angular_max", v_angular_max_);
5352
node->get_parameter("controller.slowdown_radius", slowdown_radius_);
5453
control_law_ = std::make_unique<nav2_graceful_controller::SmoothControlLaw>(
@@ -94,8 +93,6 @@ Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
9493
v_linear_max_ = parameter.as_double();
9594
} else if (name == "controller.v_angular_max") {
9695
v_angular_max_ = parameter.as_double();
97-
} else if (name == "controller.v_angular_min") {
98-
v_angular_min_ = parameter.as_double();
9996
} else if (name == "controller.slowdown_radius") {
10097
slowdown_radius_ = parameter.as_double();
10198
}
@@ -111,20 +108,19 @@ Controller::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
111108
return result;
112109
}
113110

114-
geometry_msgs::msg::Twist Controller::rotateToTarget(const double & angle_to_target)
111+
geometry_msgs::msg::Twist Controller::computeRotateToHeadingCommand(
112+
const double & angular_distance_to_heading,
113+
const geometry_msgs::msg::Twist & current_velocity,
114+
const double & dt)
115115
{
116-
geometry_msgs::msg::Twist vel;
117-
vel.linear.x = 0.0;
118-
vel.angular.z = 0.0;
119-
if(angle_to_target > 0) {
120-
vel.angular.z = std::clamp(1.0 * angle_to_target * v_angular_max_,
121-
v_angular_min_, v_angular_max_);
122-
} else if (angle_to_target < 0) {
123-
vel.angular.z = std::clamp(1.0 * angle_to_target * v_angular_max_,
124-
-v_angular_max_, -v_angular_min_);
125-
}
126-
return vel;
116+
geometry_msgs::msg::Twist cmd_vel;
117+
const double sign = angular_distance_to_heading > 0.0 ? 1.0 : -1.0;
118+
const double angular_vel = sign * rotate_to_heading_angular_vel_;
119+
const double min_feasible_angular_speed = current_velocity.angular.z - rotate_to_heading_max_angular_accel_ * dt;
120+
const double max_feasible_angular_speed = current_velocity.angular.z + rotate_to_heading_max_angular_accel_ * dt;
121+
cmd_vel.angular.z =
122+
std::clamp(angular_vel, min_feasible_angular_speed, max_feasible_angular_speed);
123+
return cmd_vel;
127124
}
128125

129-
130126
} // namespace opennav_docking

nav2_docking/opennav_docking/src/docking_server.cpp

+24-7
Original file line numberDiff line numberDiff line change
@@ -41,13 +41,16 @@ DockingServer::DockingServer(const rclcpp::NodeOptions & options)
4141
declare_parameter("dock_backwards", false);
4242
declare_parameter("dock_prestaging_tolerance", 0.5);
4343
declare_parameter("backward_blind", false);
44+
declare_parameter("odom_topic", "odom");
45+
declare_parameter("backward_rotation_tolerance", 0.02);
4446
}
4547

4648
nav2_util::CallbackReturn
4749
DockingServer::on_configure(const rclcpp_lifecycle::State & state)
4850
{
4951
RCLCPP_INFO(get_logger(), "Configuring %s", get_name());
5052
auto node = shared_from_this();
53+
std::string odom_topic;
5154

5255
get_parameter("controller_frequency", controller_frequency_);
5356
get_parameter("initial_perception_timeout", initial_perception_timeout_);
@@ -61,14 +64,20 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state)
6164
get_parameter("dock_backwards", dock_backwards_);
6265
get_parameter("dock_prestaging_tolerance", dock_prestaging_tolerance_);
6366
get_parameter("backward_blind", backward_blind_);
67+
get_parameter("odom_topic", odom_topic);
68+
get_parameter("backward_rotation_tolerance",backward_rotation_tolerance_);
6469
if(backward_blind_ && !dock_backwards_) {
6570
RCLCPP_ERROR(get_logger(), "backward_blind is enabled when dock_backwards is disabled.");
6671
return nav2_util::CallbackReturn::FAILURE;
6772
}
73+
if(odom_topic.empty()) {
74+
odom_topic = "odom";
75+
}
6876
RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
6977

7078
vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel", 1);
7179
tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(node->get_clock());
80+
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node, odom_topic);
7281

7382
double action_server_result_timeout;
7483
nav2_util::declare_parameter_if_not_declared(
@@ -160,6 +169,7 @@ DockingServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
160169
curr_dock_type_.clear();
161170
controller_.reset();
162171
vel_publisher_.reset();
172+
odom_sub_.reset();
163173
return nav2_util::CallbackReturn::SUCCESS;
164174
}
165175

@@ -415,18 +425,25 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po
415425
{
416426
rclcpp::Rate loop_rate(controller_frequency_);
417427
geometry_msgs::msg::PoseStamped robot_pose;
418-
double angle_to_goal;
428+
geometry_msgs::msg::PoseStamped target_pose = dock_pose;
419429
auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
430+
auto current_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
431+
double angular_distance_to_heading;
432+
const double dt = 1.0 / controller_frequency_;
433+
target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
434+
tf2::getYaw(target_pose.pose.orientation) + M_PI);
420435
while(rclcpp::ok()) {
421436
robot_pose = getRobotPoseInFrame(dock_pose.header.frame_id);
422-
angle_to_goal = angles::shortest_angular_distance(tf2::getYaw(robot_pose.pose.orientation),
423-
atan2(robot_pose.pose.position.y - dock_pose.pose.position.y,
424-
robot_pose.pose.position.x - dock_pose.pose.position.x));
425-
if(fabs(angle_to_goal) < 0.02) {
437+
angular_distance_to_heading = angles::shortest_angular_distance(
438+
tf2::getYaw(robot_pose.pose.orientation),
439+
tf2::getYaw(target_pose.pose.orientation));
440+
if(fabs(angular_distance_to_heading) < backward_rotation_tolerance_) {
426441
break;
427442
}
428-
command->header.stamp = now();
429-
command->twist = controller_->rotateToTarget(angle_to_goal);
443+
current_vel->twist.angular.z = odom_sub_->getTwist().theta;
444+
command->twist = controller_->computeRotateToHeadingCommand(angular_distance_to_heading,
445+
current_vel->twist, dt);
446+
command->header = robot_pose.header;
430447
vel_publisher_->publish(std::move(command));
431448
loop_rate.sleep();
432449
}

0 commit comments

Comments
 (0)