@@ -41,13 +41,16 @@ DockingServer::DockingServer(const rclcpp::NodeOptions & options)
41
41
declare_parameter (" dock_backwards" , false );
42
42
declare_parameter (" dock_prestaging_tolerance" , 0.5 );
43
43
declare_parameter (" backward_blind" , false );
44
+ declare_parameter (" odom_topic" , " odom" );
45
+ declare_parameter (" backward_rotation_tolerance" , 0.02 );
44
46
}
45
47
46
48
nav2_util::CallbackReturn
47
49
DockingServer::on_configure (const rclcpp_lifecycle::State & state)
48
50
{
49
51
RCLCPP_INFO (get_logger (), " Configuring %s" , get_name ());
50
52
auto node = shared_from_this ();
53
+ std::string odom_topic;
51
54
52
55
get_parameter (" controller_frequency" , controller_frequency_);
53
56
get_parameter (" initial_perception_timeout" , initial_perception_timeout_);
@@ -61,14 +64,20 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state)
61
64
get_parameter (" dock_backwards" , dock_backwards_);
62
65
get_parameter (" dock_prestaging_tolerance" , dock_prestaging_tolerance_);
63
66
get_parameter (" backward_blind" , backward_blind_);
67
+ get_parameter (" odom_topic" , odom_topic);
68
+ get_parameter (" backward_rotation_tolerance" ,backward_rotation_tolerance_);
64
69
if (backward_blind_ && !dock_backwards_) {
65
70
RCLCPP_ERROR (get_logger (), " backward_blind is enabled when dock_backwards is disabled." );
66
71
return nav2_util::CallbackReturn::FAILURE;
67
72
}
73
+ if (odom_topic.empty ()) {
74
+ odom_topic = " odom" ;
75
+ }
68
76
RCLCPP_INFO (get_logger (), " Controller frequency set to %.4fHz" , controller_frequency_);
69
77
70
78
vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, " cmd_vel" , 1 );
71
79
tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(node->get_clock ());
80
+ odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node, odom_topic);
72
81
73
82
double action_server_result_timeout;
74
83
nav2_util::declare_parameter_if_not_declared (
@@ -160,6 +169,7 @@ DockingServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
160
169
curr_dock_type_.clear ();
161
170
controller_.reset ();
162
171
vel_publisher_.reset ();
172
+ odom_sub_.reset ();
163
173
return nav2_util::CallbackReturn::SUCCESS;
164
174
}
165
175
@@ -415,18 +425,25 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po
415
425
{
416
426
rclcpp::Rate loop_rate (controller_frequency_);
417
427
geometry_msgs::msg::PoseStamped robot_pose;
418
- double angle_to_goal ;
428
+ geometry_msgs::msg::PoseStamped target_pose = dock_pose ;
419
429
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);
420
435
while (rclcpp::ok ()) {
421
436
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_ ) {
426
441
break ;
427
442
}
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 ;
430
447
vel_publisher_->publish (std::move (command));
431
448
loop_rate.sleep ();
432
449
}
0 commit comments