Skip to content

Commit d357701

Browse files
committed
Build fixes
1 parent e1a6598 commit d357701

File tree

2 files changed

+4
-1
lines changed

2 files changed

+4
-1
lines changed

nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -95,7 +95,7 @@ class DockingServer : public nav2_util::LifecycleNode
9595
/**
9696
* @brief Perform a pure rotation to dock orientation.
9797
*/
98-
void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose);
98+
void rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose);
9999

100100

101101
/**

nav2_docking/opennav_docking/src/docking_server.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -426,13 +426,15 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po
426426
rclcpp::Rate loop_rate(controller_frequency_);
427427
geometry_msgs::msg::PoseStamped robot_pose = getRobotPoseInFrame(dock_pose.header.frame_id);
428428
double angle_to_goal;
429+
auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
429430
while(rclcpp::ok()){
430431
angle_to_goal = angles::shortest_angular_distance(tf2::getYaw(robot_pose.pose.orientation),
431432
atan2(robot_pose.pose.position.y - dock_pose.pose.position.y,
432433
robot_pose.pose.position.x - dock_pose.pose.position.x));
433434
if(fabs(angle_to_goal) > 0.1){
434435
break;
435436
}
437+
command->header.stamp = now();
436438
command = controller_->rotateToTarget(angle_to_goal);
437439
vel_publisher_->publish(command);
438440
loop_rate.sleep();
@@ -478,6 +480,7 @@ bool DockingServer::approachDock(Dock * dock, geometry_msgs::msg::PoseStamped &
478480
// Compute and publish controls
479481
auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
480482
command->header.stamp = now();
483+
geometry_msgs::msg::PoseStamped robot_pose = getRobotPoseInFrame(dock_pose.header.frame_id);
481484
if (!controller_->computeVelocityCommand(target_pose.pose, robot_pose.pose, command->twist, dock_backwards_)) {
482485
throw opennav_docking_core::FailedToControl("Failed to get control");
483486
}

0 commit comments

Comments
 (0)