Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -439,7 +439,6 @@ docking_server:
max_retries: 3
base_frame: "base_link"
fixed_frame: "odom"
dock_backwards: false
dock_prestaging_tolerance: 0.5
service_introspection_mode: "disabled"

Expand All @@ -452,6 +451,7 @@ docking_server:
use_external_detection_pose: true
use_battery_status: false # true
use_stall_detection: false # true
dock_direction: "forward"

external_detection_timeout: 1.0
external_detection_translation_x: -0.18
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,6 @@ For debugging purposes, there are several publishers which can be used with RVIZ
| max_retries | Maximum number of retries to attempt | int | 3 |
| base_frame | Robot's base frame for control law | string | "base_link" |
| fixed_frame | Fixed frame to use, recommended to be a smooth odometry frame **not** map | string | "odom" |
| dock_backwards | Whether the robot is docking with the dock forward or backward in motion | bool | false |
| dock_prestaging_tolerance | L2 distance in X,Y,Theta from the staging pose to bypass navigation | double | 0.5 |
| dock_plugins | A set of dock plugins to load | vector<string> | N/A |
| dock_database | The filepath to the dock database to use for this environment | string | N/A |
Expand Down Expand Up @@ -251,6 +250,7 @@ Note: `dock_plugins` and either `docks` or `dock_database` are required.
| docking_threshold | If not using stall detection, the pose threshold to the docking pose where `isDocked() = true` | double | 0.05 |
| staging_x_offset | Staging pose offset forward (negative) of dock pose (m) | double | -0.7 |
| staging_yaw_offset | Staging pose angle relative to dock pose (rad) | double | 0.0 |
| dock_direction | Whether the robot is docking with the dock forward or backward in motion | string | "forward" or "backward" |

Note: The external detection rotation angles are setup to work out of the box with Apriltags detectors in `image_proc` and `isaac_ros`.

Expand Down
26 changes: 14 additions & 12 deletions nav2_docking/opennav_docking/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ add_library(controller SHARED
)
target_include_directories(controller
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(controller PUBLIC
${geometry_msgs_TARGETS}
Expand All @@ -51,8 +51,8 @@ add_library(${library_name} SHARED
)
target_include_directories(${library_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(${library_name} PUBLIC
angles::angles
Expand All @@ -79,8 +79,8 @@ add_library(pose_filter SHARED
)
target_include_directories(pose_filter
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(pose_filter PUBLIC
${geometry_msgs_TARGETS}
Expand All @@ -95,8 +95,8 @@ add_executable(${executable_name}
)
target_include_directories(${executable_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(${executable_name} PRIVATE ${library_name} rclcpp::rclcpp)

Expand All @@ -107,8 +107,8 @@ add_library(simple_charging_dock SHARED
)
target_include_directories(simple_charging_dock
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(simple_charging_dock PUBLIC
${geometry_msgs_TARGETS}
Expand All @@ -121,6 +121,7 @@ target_link_libraries(simple_charging_dock PUBLIC
tf2_ros::tf2_ros
)
target_link_libraries(simple_charging_dock PRIVATE
angles::angles
nav2_util::nav2_util_core
pluginlib::pluginlib
tf2::tf2
Expand All @@ -131,8 +132,8 @@ add_library(simple_non_charging_dock SHARED
)
target_include_directories(simple_non_charging_dock
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
target_link_libraries(simple_non_charging_dock PUBLIC
${geometry_msgs_TARGETS}
Expand All @@ -145,6 +146,7 @@ target_link_libraries(simple_non_charging_dock PUBLIC
tf2_ros::tf2_ros
)
target_link_libraries(simple_non_charging_dock PRIVATE
angles::angles
nav2_util::nav2_util_core
pluginlib::pluginlib
tf2::tf2
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,12 @@
#ifndef OPENNAV_DOCKING__DOCKING_SERVER_HPP_
#define OPENNAV_DOCKING__DOCKING_SERVER_HPP_

#include <vector>
#include <functional>
#include <memory>
#include <string>
#include <mutex>
#include <functional>
#include <optional>
#include <string>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "nav2_util/lifecycle_node.hpp"
Expand Down Expand Up @@ -87,10 +88,11 @@ class DockingServer : public nav2_util::LifecycleNode
* @brief Use control law and dock perception to approach the charge dock.
* @param dock Dock instance, gets queried for refined pose and docked state.
* @param dock_pose Initial dock pose, will be refined by perception.
* @param backward If true, the robot will drive backwards.
* @returns True if dock successfully approached, False if cancelled. For
* any internal error, will throw.
*/
bool approachDock(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose);
bool approachDock(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose, bool backward);

/**
* @brief Wait for charging to begin.
Expand All @@ -102,9 +104,10 @@ class DockingServer : public nav2_util::LifecycleNode
/**
* @brief Reset the robot for another approach by controlling back to staging pose.
* @param staging_pose The target pose that will reset for another approach.
* @param backward If true, the robot will drive backwards.
* @returns True if reset is successful.
*/
bool resetApproach(const geometry_msgs::msg::PoseStamped & staging_pose);
bool resetApproach(const geometry_msgs::msg::PoseStamped & staging_pose, bool backward);

/**
* @brief Run a single iteration of the control loop to approach a pose.
Expand Down Expand Up @@ -242,7 +245,7 @@ class DockingServer : public nav2_util::LifecycleNode
// This is our fixed frame for controlling - typically "odom"
std::string fixed_frame_;
// Does the robot drive backwards onto the dock? Default is forwards
bool dock_backwards_;
std::optional<bool> dock_backwards_;
// The tolerance to the dock's staging pose not requiring navigation
double dock_prestaging_tolerance_;

Expand Down
17 changes: 17 additions & 0 deletions nav2_docking/opennav_docking/include/opennav_docking/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include "nav2_util/geometry_utils.hpp"
#include "angles/angles.h"
#include "opennav_docking/types.hpp"
#include "opennav_docking_core/charging_dock.hpp"
#include "tf2/utils.hpp"

namespace utils
Expand All @@ -33,6 +34,7 @@ using rclcpp::ParameterType::PARAMETER_STRING;
using rclcpp::ParameterType::PARAMETER_STRING_ARRAY;
using rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY;
using nav2_util::geometry_utils::orientationAroundZAxis;
using opennav_docking_core::DockDirection;

/**
* @brief Parse a yaml file to obtain docks
Expand Down Expand Up @@ -183,6 +185,21 @@ inline double l2Norm(const geometry_msgs::msg::Pose & a, const geometry_msgs::ms
delta_angle * delta_angle);
}

inline DockDirection getDockDirectionFromString(const std::string & direction)
{
auto upper_direction = direction;
std::transform(
upper_direction.begin(), upper_direction.end(), upper_direction.begin(), ::toupper);

if (upper_direction == "FORWARD") {
return DockDirection::FORWARD;
} else if (upper_direction == "BACKWARD") {
return DockDirection::BACKWARD;
} else {
return DockDirection::UNKNOWN;
}
}

} // namespace utils

#endif // OPENNAV_DOCKING__UTILS_HPP_
44 changes: 32 additions & 12 deletions nav2_docking/opennav_docking/src/docking_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
declare_parameter("max_retries", 3);
declare_parameter("base_frame", "base_link");
declare_parameter("fixed_frame", "odom");
declare_parameter("dock_backwards", false);
declare_parameter("dock_backwards", rclcpp::PARAMETER_BOOL);
declare_parameter("dock_prestaging_tolerance", 0.5);
}

Expand All @@ -57,10 +57,19 @@
get_parameter("max_retries", max_retries_);
get_parameter("base_frame", base_frame_);
get_parameter("fixed_frame", fixed_frame_);
get_parameter("dock_backwards", dock_backwards_);
get_parameter("dock_prestaging_tolerance", dock_prestaging_tolerance_);
RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);

bool dock_backwards;
try {
if (get_parameter("dock_backwards", dock_backwards)) {
dock_backwards_ = dock_backwards;
RCLCPP_WARN(get_logger(), "Parameter dock_backwards is deprecated. "
"Please use the dock_direction parameter in your dock plugin instead.");
}
} catch (rclcpp::exceptions::ParameterUninitializedException & ex) {

Check warning on line 70 in nav2_docking/opennav_docking/src/docking_server.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_docking/opennav_docking/src/docking_server.cpp#L70

Added line #L70 was not covered by tests
}

vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel", 1);
tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(node->get_clock());

Expand Down Expand Up @@ -155,6 +164,7 @@
curr_dock_type_.clear();
controller_.reset();
vel_publisher_.reset();
dock_backwards_.reset();
return nav2_util::CallbackReturn::SUCCESS;
}

Expand Down Expand Up @@ -274,12 +284,17 @@
doInitialPerception(dock, dock_pose);
RCLCPP_INFO(get_logger(), "Successful initial dock detection");

// Get the direction of the movement
bool dock_backward = dock_backwards_.has_value() ?
dock_backwards_.value() :

Check warning on line 289 in nav2_docking/opennav_docking/src/docking_server.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_docking/opennav_docking/src/docking_server.cpp#L289

Added line #L289 was not covered by tests
(dock->plugin->getDockDirection() == opennav_docking_core::DockDirection::BACKWARD);

// Docking control loop: while not docked, run controller
rclcpp::Time dock_contact_time;
while (rclcpp::ok()) {
try {
// Approach the dock using control law
if (approachDock(dock, dock_pose)) {
if (approachDock(dock, dock_pose, dock_backward)) {
// We are docked, wait for charging to begin
RCLCPP_INFO(
get_logger(), "Made contact with dock, waiting for charge to start (if applicable).");
Expand Down Expand Up @@ -312,7 +327,7 @@
}

// Reset to staging pose to try again
if (!resetApproach(dock->getStagingPose())) {
if (!resetApproach(dock->getStagingPose(), dock_backward)) {
// Cancelled, preempted, or shutting down
stashDockData(goal->use_dock_id, dock, false);
publishZeroVelocity();
Expand Down Expand Up @@ -409,11 +424,13 @@
}
}

bool DockingServer::approachDock(Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose)
bool DockingServer::approachDock(
Dock * dock, geometry_msgs::msg::PoseStamped & dock_pose, bool backward)
{
rclcpp::Rate loop_rate(controller_frequency_);
auto start = this->now();
auto timeout = rclcpp::Duration::from_seconds(dock_approach_timeout_);

while (rclcpp::ok()) {
publishDockingFeedback(DockRobot::Feedback::CONTROLLING);

Expand All @@ -440,7 +457,7 @@

// Make sure that the target pose is pointing at the robot when moving backwards
// This is to ensure that the robot doesn't try to dock from the wrong side
if (dock_backwards_) {
if (backward) {
target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
tf2::getYaw(target_pose.pose.orientation) + M_PI);
}
Expand All @@ -458,9 +475,7 @@
// Compute and publish controls
auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
command->header.stamp = now();
if (!controller_->computeVelocityCommand(target_pose.pose, command->twist, true,
dock_backwards_))
{
if (!controller_->computeVelocityCommand(target_pose.pose, command->twist, true, backward)) {
throw opennav_docking_core::FailedToControl("Failed to get control");
}
vel_publisher_->publish(std::move(command));
Expand Down Expand Up @@ -507,7 +522,8 @@
return false;
}

bool DockingServer::resetApproach(const geometry_msgs::msg::PoseStamped & staging_pose)
bool DockingServer::resetApproach(
const geometry_msgs::msg::PoseStamped & staging_pose, bool backward)
{
rclcpp::Rate loop_rate(controller_frequency_);
auto start = this->now();
Expand All @@ -527,7 +543,7 @@
command->header.stamp = now();
if (getCommandToPose(
command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_, false,
!dock_backwards_))
!backward))
{
return true;
}
Expand Down Expand Up @@ -653,9 +669,13 @@
// Get command to approach staging pose
auto command = std::make_unique<geometry_msgs::msg::TwistStamped>();
command->header.stamp = now();
bool dock_backward = dock_backwards_.has_value() ?
dock_backwards_.value() :

Check warning on line 673 in nav2_docking/opennav_docking/src/docking_server.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_docking/opennav_docking/src/docking_server.cpp#L673

Added line #L673 was not covered by tests
(dock->getDockDirection() == opennav_docking_core::DockDirection::BACKWARD);

if (getCommandToPose(
command->twist, staging_pose, undock_linear_tolerance_, undock_angular_tolerance_, false,
!dock_backwards_))
!dock_backward))
{
RCLCPP_INFO(get_logger(), "Robot has reached staging pose");
// Have reached staging_pose
Expand Down
12 changes: 12 additions & 0 deletions nav2_docking/opennav_docking/src/simple_charging_dock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include "nav2_util/node_utils.hpp"
#include "opennav_docking/simple_charging_dock.hpp"
#include "opennav_docking/utils.hpp"

namespace opennav_docking
{
Expand Down Expand Up @@ -78,6 +79,10 @@ void SimpleChargingDock::configure(
nav2_util::declare_parameter_if_not_declared(
node_, name + ".staging_yaw_offset", rclcpp::ParameterValue(0.0));

// Direction of docking
nav2_util::declare_parameter_if_not_declared(
node_, name + ".dock_direction", rclcpp::ParameterValue(std::string("forward")));

node_->get_parameter(name + ".use_battery_status", use_battery_status_);
node_->get_parameter(name + ".use_external_detection_pose", use_external_detection_pose_);
node_->get_parameter(name + ".external_detection_timeout", external_detection_timeout_);
Expand All @@ -98,6 +103,13 @@ void SimpleChargingDock::configure(
node_->get_parameter(name + ".staging_x_offset", staging_x_offset_);
node_->get_parameter(name + ".staging_yaw_offset", staging_yaw_offset_);

std::string dock_direction;
node_->get_parameter(name + ".dock_direction", dock_direction);
dock_direction_ = utils::getDockDirectionFromString(dock_direction);
if (dock_direction_ == opennav_docking_core::DockDirection::UNKNOWN) {
throw std::runtime_error{"Dock direction is not valid. Valid options are: forward or backward"};
}

// Setup filter
double filter_coef;
node_->get_parameter(name + ".filter_coef", filter_coef);
Expand Down
Loading
Loading