Skip to content

Commit

Permalink
Build fixes
Browse files Browse the repository at this point in the history
Signed-off-by: Jakubach <[email protected]>
  • Loading branch information
Jakubach committed Nov 13, 2024
1 parent 5cd1739 commit e1a6598
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 4 deletions.
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 DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_pose);


/**
Expand Down Expand Up @@ -255,7 +255,7 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po
// depending on the initial robot orientation and k_phi, k_delta.
bool initial_rotation_;
// Enable aproaching a docking station only with initial detection without updates
bool backward_blind;
bool backward_blind_;

// This is a class member so it can be accessed in publish feedback
rclcpp::Time action_start_time_;
Expand Down
3 changes: 1 addition & 2 deletions nav2_docking/opennav_docking/src/docking_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,7 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state)
get_parameter("initial_rotation", initial_rotation_);
get_parameter("backward_blind", backward_blind_);
if(backward_blind_ && !dock_backwards_){
RCLCPP_ERROR(get_logger(), "Docking server configuration is invalid.
backward_blind is enabled when dock_backwards is disabled.");
RCLCPP_ERROR(get_logger(), "backward_blind is enabled when dock_backwards is disabled.");
return nav2_util::CallbackReturn::FAILURE;
} else{
// If you have backward_blind and dock_backward then
Expand Down

0 comments on commit e1a6598

Please sign in to comment.