Skip to content

Commit

Permalink
Build fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
Jakubach committed Nov 13, 2024
1 parent e1a6598 commit d357701
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ class DockingServer : public nav2_util::LifecycleNode
/**
* @brief Perform a pure rotation to dock orientation.
*/
void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose);
void rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose);


/**
Expand Down
3 changes: 3 additions & 0 deletions nav2_docking/opennav_docking/src/docking_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -426,13 +426,15 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po
rclcpp::Rate loop_rate(controller_frequency_);
geometry_msgs::msg::PoseStamped robot_pose = getRobotPoseInFrame(dock_pose.header.frame_id);
double angle_to_goal;
auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
while(rclcpp::ok()){
angle_to_goal = angles::shortest_angular_distance(tf2::getYaw(robot_pose.pose.orientation),
atan2(robot_pose.pose.position.y - dock_pose.pose.position.y,
robot_pose.pose.position.x - dock_pose.pose.position.x));
if(fabs(angle_to_goal) > 0.1){
break;
}
command->header.stamp = now();
command = controller_->rotateToTarget(angle_to_goal);
vel_publisher_->publish(command);
loop_rate.sleep();
Expand Down Expand Up @@ -478,6 +480,7 @@ bool DockingServer::approachDock(Dock * dock, geometry_msgs::msg::PoseStamped &
// Compute and publish controls
auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
command->header.stamp = now();
geometry_msgs::msg::PoseStamped robot_pose = getRobotPoseInFrame(dock_pose.header.frame_id);
if (!controller_->computeVelocityCommand(target_pose.pose, robot_pose.pose, command->twist, dock_backwards_)) {
throw opennav_docking_core::FailedToControl("Failed to get control");
}
Expand Down

0 comments on commit d357701

Please sign in to comment.