Skip to content

Commit 4345fc5

Browse files
committed
CI fixes
Signed-off-by: Jakubach <[email protected]>
1 parent a6f669c commit 4345fc5

File tree

4 files changed

+21
-14
lines changed

4 files changed

+21
-14
lines changed

nav2_docking/opennav_docking/include/opennav_docking/controller.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,8 @@ class Controller
4545
* @returns True if command is valid, false otherwise.
4646
*/
4747
bool computeVelocityCommand(
48-
const geometry_msgs::msg::Pose & pose,const geometry_msgs::msg::Pose & robot_pose, geometry_msgs::msg::Twist & cmd,
49-
bool backward = false);
48+
const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Pose & robot_pose,
49+
geometry_msgs::msg::Twist & cmd, bool backward = false);
5050

5151
/**
5252
* @brief Callback executed when a parameter change is detected

nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -250,7 +250,9 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po
250250
bool dock_backwards_;
251251
// The tolerance to the dock's staging pose not requiring navigation
252252
double dock_prestaging_tolerance_;
253-
// Enable a rotation in place to the goal before starting the path. The control law may generate large sweeping arcs to the goal pose, depending on the initial robot orientation and k_phi, k_delta.
253+
// Enable a rotation in place to the goal before starting the path.
254+
// The control law may generate large sweeping arcs to the goal pose,
255+
// depending on the initial robot orientation and k_phi, k_delta.
254256
bool initial_rotation_;
255257
// Enable aproaching a docking station only with initial detection without updates
256258
bool backward_blind;

nav2_docking/opennav_docking/src/controller.cpp

+7-6
Original file line numberDiff line numberDiff line change
@@ -61,8 +61,8 @@ Controller::Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node)
6161
}
6262

6363
bool Controller::computeVelocityCommand(
64-
const geometry_msgs::msg::Pose & pose,const geometry_msgs::msg::Pose & robot_pose, geometry_msgs::msg::Twist & cmd,
65-
bool backward)
64+
const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Pose & robot_pose,
65+
geometry_msgs::msg::Twist & cmd, bool backward)
6666
{
6767
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
6868
cmd = control_law_->calculateRegularVelocity(pose,robot_pose, backward);
@@ -117,10 +117,11 @@ geometry_msgs::msg::Twist Controller::rotateToTarget(const double & angle_to_tar
117117
vel.linear.x = 0.0;
118118
vel.angular.z = 0.0;
119119
if(angle_to_target > 0) {
120-
vel.angular.z = std::clamp(1.0 * angle_to_target * v_angular_max_, v_angular_min_, v_angular_max_);
121-
}
122-
else if (angle_to_target < 0) {
123-
vel.angular.z = std::clamp(1.0 * angle_to_target * v_angular_max_, -v_angular_max_, -v_angular_min_);
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_);
124125
}
125126
return vel;
126127
}

nav2_docking/opennav_docking/src/docking_server.cpp

+9-5
Original file line numberDiff line numberDiff line change
@@ -64,11 +64,13 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state)
6464
get_parameter("initial_rotation", initial_rotation_);
6565
get_parameter("backward_blind", backward_blind_);
6666
if(backward_blind_ && !dock_backwards_){
67-
RCLCPP_ERROR(get_logger(), "Docking server configuration is invalid. backward_blind is enabled when dock_backwards is disabled.");
67+
RCLCPP_ERROR(get_logger(), "Docking server configuration is invalid.
68+
backward_blind is enabled when dock_backwards is disabled.");
6869
return nav2_util::CallbackReturn::FAILURE;
69-
}
70-
else{
71-
// If you have backward_blind and dock_backward then we know we need to do the initial rotation to go from forward to reverse before doing the rest of the procedure. The initial_rotation would thus always be true.
70+
} else{
71+
// If you have backward_blind and dock_backward then
72+
//we know we need to do the initial rotation to go from forward to reverse
73+
//before doing the rest of the procedure. The initial_rotation would thus always be true.
7274
initial_rotation_ = true;
7375
}
7476
RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
@@ -426,7 +428,9 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po
426428
geometry_msgs::msg::PoseStamped robot_pose = getRobotPoseInFrame(dock_pose.header.frame_id);
427429
double angle_to_goal;
428430
while(rclcpp::ok()){
429-
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));
431+
angle_to_goal = angles::shortest_angular_distance(tf2::getYaw(robot_pose.pose.orientation),
432+
atan2(robot_pose.pose.position.y - dock_pose.pose.position.y,
433+
robot_pose.pose.position.x - dock_pose.pose.position.x));
430434
if(fabs(angle_to_goal) > 0.1){
431435
break;
432436
}

0 commit comments

Comments
 (0)