Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add a timeout to the wait for transforms step of the costmap activation. #3866

Merged
merged 5 commits into from
Oct 12, 2023
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
5 changes: 4 additions & 1 deletion nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,10 @@ ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Activating");

costmap_ros_->activate();
const auto costmap_ros_state = costmap_ros_->activate();
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
return nav2_util::CallbackReturn::FAILURE;
}
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->activate();
Expand Down
9 changes: 5 additions & 4 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -360,7 +360,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
bool always_send_full_costmap_{false};
std::string footprint_;
float footprint_padding_{0};
std::string global_frame_; ///< The global frame for the costmap
std::string global_frame_; ///< The global frame for the costmap
int map_height_meters_{0};
double map_publish_frequency_{0};
double map_update_frequency_{0};
Expand All @@ -374,11 +374,12 @@ class Costmap2DROS : public nav2_util::LifecycleNode
std::vector<std::string> filter_names_;
std::vector<std::string> filter_types_;
double resolution_{0};
std::string robot_base_frame_; ///< The frame_id of the robot base
std::string robot_base_frame_; ///< The frame_id of the robot base
double robot_radius_;
bool rolling_window_{false}; ///< Whether to use a rolling window version of the costmap
bool rolling_window_{false}; ///< Whether to use a rolling window version of the costmap
bool track_unknown_space_{false};
double transform_tolerance_{0}; ///< The timeout before transform errors
double transform_tolerance_{0}; ///< The timeout before transform errors
double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors

// Derived parameters
bool use_radius_{false};
Expand Down
29 changes: 22 additions & 7 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,7 @@ void Costmap2DROS::init()
declare_parameter("rolling_window", rclcpp::ParameterValue(false));
declare_parameter("track_unknown_space", rclcpp::ParameterValue(false));
declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.3));
declare_parameter("initial_transform_timeout", rclcpp::ParameterValue(60.0));
declare_parameter("trinary_costmap", rclcpp::ParameterValue(true));
declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
Expand Down Expand Up @@ -265,20 +266,16 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Activating");

footprint_pub_->on_activate();
costmap_publisher_->on_activate();

for (auto & layer_pub : layer_publishers_) {
layer_pub->on_activate();
}

// First, make sure that the transform between the robot base frame
// and the global frame is available

std::string tf_error;

RCLCPP_INFO(get_logger(), "Checking transform");
rclcpp::Rate r(2);
const auto initial_transform_timeout = rclcpp::Duration::from_seconds(
initial_transform_timeout_);
const auto initial_transform_timeout_point = now() + initial_transform_timeout;
while (rclcpp::ok() &&
!tf_buffer_->canTransform(
global_frame_, robot_base_frame_, tf2::TimePointZero, &tf_error))
Expand All @@ -288,12 +285,29 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/)
" to become available, tf error: %s",
robot_base_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());

// Check timeout
if (now() > initial_transform_timeout_point) {
RCLCPP_ERROR(
get_logger(), "Failed to activate %s because transform from %s to %s did not become available before timeout",
get_name(), robot_base_frame_.c_str(), global_frame_.c_str());

return nav2_util::CallbackReturn::FAILURE;
}

// The error string will accumulate and errors will typically be the same, so the last
// will do for the warning above. Reset the string here to avoid accumulation
tf_error.clear();
r.sleep();
}

// Activate publishers
footprint_pub_->on_activate();
costmap_publisher_->on_activate();

for (auto & layer_pub : layer_publishers_) {
layer_pub->on_activate();
}

// Create a thread to handle updating the map
stopped_ = true; // to active plugins
stop_updates_ = false;
Expand Down Expand Up @@ -386,6 +400,7 @@ Costmap2DROS::getParameters()
get_parameter("rolling_window", rolling_window_);
get_parameter("track_unknown_space", track_unknown_space_);
get_parameter("transform_tolerance", transform_tolerance_);
get_parameter("initial_transform_timeout", initial_transform_timeout_);
get_parameter("update_frequency", map_update_frequency_);
get_parameter("width", map_width_meters_);
get_parameter("plugins", plugin_names_);
Expand Down
5 changes: 5 additions & 0 deletions nav2_costmap_2d/test/unit/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,3 +55,8 @@ ament_add_gtest(denoise_layer_test denoise_layer_test.cpp image_test.cpp image_p
target_link_libraries(denoise_layer_test
nav2_costmap_2d_core layers
)

ament_add_gtest(lifecycle_test lifecycle_test.cpp)
target_link_libraries(lifecycle_test
nav2_costmap_2d_core
)
54 changes: 54 additions & 0 deletions nav2_costmap_2d/test/unit/lifecycle_test.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <memory>

#include "gtest/gtest.h"

#include "nav2_costmap_2d/costmap_2d_ros.hpp"
#include "rclcpp/rclcpp.hpp"
#include "lifecycle_msgs/msg/state.hpp"


TEST(LifecylceTest, CheckInitialTfTimeout) {
rclcpp::init(0, nullptr);

auto costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>("test_costmap");
costmap->set_parameter({"initial_transform_timeout", 0.0});

std::thread spin_thread{[costmap]() {rclcpp::spin(costmap->get_node_base_interface());}};

{
const auto state_after_configure = costmap->configure();
ASSERT_EQ(state_after_configure.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
// Without providing the transform from global to robot base the activation should fail
// and the costmap should transition into the inactive state.
const auto state_after_activate = costmap->activate();
ASSERT_EQ(state_after_activate.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
}

// Set a dummy transform from global to robot base
geometry_msgs::msg::TransformStamped transform_global_to_robot{};
transform_global_to_robot.header.frame_id = costmap->getGlobalFrameID();
transform_global_to_robot.child_frame_id = costmap->getBaseFrameID();
costmap->getTfBuffer()->setTransform(transform_global_to_robot, "test", true);
// Now the costmap should successful transition into the active state
{
const auto state_after_activate = costmap->activate();
ASSERT_EQ(state_after_activate.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
}

rclcpp::shutdown();
if (spin_thread.joinable()) {
spin_thread.join();
}
}
5 changes: 4 additions & 1 deletion nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,10 @@ PlannerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
plan_publisher_->on_activate();
action_server_pose_->activate();
action_server_poses_->activate();
costmap_ros_->activate();
const auto costmap_ros_state = costmap_ros_->activate();
if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
return nav2_util::CallbackReturn::FAILURE;
}

PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
Expand Down