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 PoseProgressChecker #3530

Merged
Merged
Show file tree
Hide file tree
Changes from 5 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
7 changes: 6 additions & 1 deletion nav2_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,10 @@ set(dependencies
add_library(simple_progress_checker SHARED plugins/simple_progress_checker.cpp)
ament_target_dependencies(simple_progress_checker ${dependencies})

add_library(rotation_progress_checker SHARED plugins/rotation_progress_checker.cpp)
target_link_libraries(rotation_progress_checker simple_progress_checker)
ament_target_dependencies(rotation_progress_checker ${dependencies})

add_library(simple_goal_checker SHARED plugins/simple_goal_checker.cpp)
ament_target_dependencies(simple_goal_checker ${dependencies})

Expand Down Expand Up @@ -79,7 +83,7 @@ target_link_libraries(${executable_name} ${library_name})

rclcpp_components_register_nodes(${library_name} "nav2_controller::ControllerServer")

install(TARGETS simple_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
install(TARGETS simple_progress_checker rotation_progress_checker simple_goal_checker stopped_goal_checker ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand All @@ -102,6 +106,7 @@ endif()

ament_export_include_directories(include)
ament_export_libraries(simple_progress_checker
rotation_progress_checker
simple_goal_checker
stopped_goal_checker
${library_name})
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// Copyright (c) 2023 Dexory
//
// 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.

#ifndef NAV2_CONTROLLER__PLUGINS__ROTATION_PROGRESS_CHECKER_HPP_
#define NAV2_CONTROLLER__PLUGINS__ROTATION_PROGRESS_CHECKER_HPP_

#include <string>
#include <vector>
#include "rclcpp/rclcpp.hpp"
#include "nav2_controller/plugins/simple_progress_checker.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

namespace nav2_controller
{
/**
* @class RotationProgressChecker
* @brief This plugin is used to check the position and the angle of the robot to make sure
* that it is actually progressing or rotating towards a goal.
*/

class RotationProgressChecker : public SimpleProgressChecker
{
public:
void initialize(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const std::string & plugin_name) override;
bool check(geometry_msgs::msg::PoseStamped & current_pose) override;

protected:
/**
* @brief Calculates robots movement from baseline pose
* @param pose Current pose of the robot
* @return true, if movement is greater than radius_, or false
*/
bool is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose);
doisyg marked this conversation as resolved.
Show resolved Hide resolved

static double pose_angle_distance(
doisyg marked this conversation as resolved.
Show resolved Hide resolved
const geometry_msgs::msg::Pose2D &,
const geometry_msgs::msg::Pose2D &);

double required_movement_angle_;

// Dynamic parameters handler
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
std::string plugin_name_;

/**
* @brief Callback executed when a paramter change is detected
* @param parameters list of changed parameters
*/
rcl_interfaces::msg::SetParametersResult
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
};
} // namespace nav2_controller

#endif // NAV2_CONTROLLER__PLUGINS__ROTATION_PROGRESS_CHECKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,10 @@ class SimpleProgressChecker : public nav2_core::ProgressChecker
*/
void reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose);

static double pose_distance(
const geometry_msgs::msg::Pose2D &,
const geometry_msgs::msg::Pose2D &);

rclcpp::Clock::SharedPtr clock_;

double radius_;
Expand Down
5 changes: 5 additions & 0 deletions nav2_controller/plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,11 @@
<description>Checks if distance between current and previous pose is above a threshold</description>
</class>
</library>
<library path="rotation_progress_checker">
<class type="nav2_controller::RotationProgressChecker" base_class_type="nav2_core::ProgressChecker">
<description>Checks if distance and angle between current and previous pose is above a threshold</description>
</class>
</library>
<library path="simple_goal_checker">
<class type="nav2_controller::SimpleGoalChecker" base_class_type="nav2_core::GoalChecker">
<description>Checks if current pose is within goal window for x,y and yaw</description>
Expand Down
97 changes: 97 additions & 0 deletions nav2_controller/plugins/rotation_progress_checker.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
// Copyright (c) 2023 Dexory
//
// 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 "nav2_controller/plugins/rotation_progress_checker.hpp"
#include <cmath>
#include <string>
#include <memory>
#include <vector>
#include "angles/angles.h"
#include "nav_2d_utils/conversions.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose2_d.hpp"
#include "nav2_util/node_utils.hpp"
#include "pluginlib/class_list_macros.hpp"

using rcl_interfaces::msg::ParameterType;
using std::placeholders::_1;

namespace nav2_controller
{

void RotationProgressChecker::initialize(
doisyg marked this conversation as resolved.
Show resolved Hide resolved
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const std::string & plugin_name)
{
plugin_name_ = plugin_name;
SimpleProgressChecker::initialize(parent, plugin_name);
auto node = parent.lock();

nav2_util::declare_parameter_if_not_declared(
node, plugin_name + ".required_movement_angle", rclcpp::ParameterValue(0.5));
node->get_parameter_or(plugin_name + ".required_movement_angle", required_movement_angle_, 0.5);

// Add callback for dynamic parameters
dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(&RotationProgressChecker::dynamicParametersCallback, this, _1));
}

bool RotationProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose)
{
// relies on short circuit evaluation to not call is_robot_moved_enough if
// baseline_pose is not set.
geometry_msgs::msg::Pose2D current_pose2d;
current_pose2d = nav_2d_utils::poseToPose2D(current_pose.pose);

if ((!baseline_pose_set_) || (RotationProgressChecker::is_robot_moved_enough(current_pose2d))) {
reset_baseline_pose(current_pose2d);
return true;
}
return !((clock_->now() - baseline_time_) > time_allowance_);
}

bool RotationProgressChecker::is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose)
{
return pose_distance(pose, baseline_pose_) > radius_ ||
pose_angle_distance(pose, baseline_pose_) > required_movement_angle_;
}

double RotationProgressChecker::pose_angle_distance(
const geometry_msgs::msg::Pose2D & pose1,
const geometry_msgs::msg::Pose2D & pose2)
{
return abs(angles::shortest_angular_distance(pose1.theta, pose2.theta));
}

rcl_interfaces::msg::SetParametersResult
RotationProgressChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
{
rcl_interfaces::msg::SetParametersResult result;
for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();

if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == plugin_name_ + ".required_movement_angle") {
required_movement_angle_ = parameter.as_double();
}
}
}
result.successful = true;
return result;
}

} // namespace nav2_controller

PLUGINLIB_EXPORT_CLASS(nav2_controller::RotationProgressChecker, nav2_core::ProgressChecker)
4 changes: 1 addition & 3 deletions nav2_controller/plugins/simple_progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,6 @@ using std::placeholders::_1;

namespace nav2_controller
{
static double pose_distance(const geometry_msgs::msg::Pose2D &, const geometry_msgs::msg::Pose2D &);

void SimpleProgressChecker::initialize(
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
const std::string & plugin_name)
Expand Down Expand Up @@ -85,7 +83,7 @@ bool SimpleProgressChecker::is_robot_moved_enough(const geometry_msgs::msg::Pose
return pose_distance(pose, baseline_pose_) > radius_;
}

static double pose_distance(
double SimpleProgressChecker::pose_distance(
const geometry_msgs::msg::Pose2D & pose1,
const geometry_msgs::msg::Pose2D & pose2)
{
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/plugins/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
ament_add_gtest(pctest progress_checker.cpp)
target_link_libraries(pctest simple_progress_checker)
target_link_libraries(pctest simple_progress_checker rotation_progress_checker)
ament_add_gtest(gctest goal_checker.cpp)
target_link_libraries(gctest simple_goal_checker stopped_goal_checker)
10 changes: 10 additions & 0 deletions nav2_controller/plugins/test/goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,16 @@ TEST(VelocityIterator, goal_checker_reset)
EXPECT_TRUE(true);
}

TEST(VelocityIterator, stopped_goal_checker_reset)
{
auto x = std::make_shared<TestLifecycleNode>("stopped_goal_checker");

nav2_core::GoalChecker * sgc = new StoppedGoalChecker;
sgc->reset();
delete sgc;
EXPECT_TRUE(true);
}

TEST(VelocityIterator, two_checks)
{
auto x = std::make_shared<TestLifecycleNode>("goal_checker");
Expand Down
58 changes: 50 additions & 8 deletions nav2_controller/plugins/test/progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,13 @@

#include "gtest/gtest.h"
#include "nav2_controller/plugins/simple_progress_checker.hpp"
#include "nav2_controller/plugins/rotation_progress_checker.hpp"
#include "nav_2d_utils/conversions.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/geometry_utils.hpp"

using nav2_controller::SimpleProgressChecker;
using nav2_controller::RotationProgressChecker;

class TestLifecycleNode : public nav2_util::LifecycleNode
{
Expand Down Expand Up @@ -83,17 +86,19 @@ class TestLifecycleNode : public nav2_util::LifecycleNode

void checkMacro(
nav2_core::ProgressChecker & pc,
double x0, double y0,
double x1, double y1,
double x0, double y0, double theta0,
double x1, double y1, double theta1,
int delay,
bool expected_result)
{
pc.reset();
geometry_msgs::msg::PoseStamped pose0, pose1;
pose0.pose.position.x = x0;
pose0.pose.position.y = y0;
pose0.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(theta0);
pose1.pose.position.x = x1;
pose1.pose.position.y = y1;
pose1.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(theta1);
EXPECT_TRUE(pc.check(pose0));
rclcpp::sleep_for(std::chrono::seconds(delay));
if (expected_result) {
Expand All @@ -119,12 +124,49 @@ TEST(SimpleProgressChecker, unit_tests)

SimpleProgressChecker pc;
pc.initialize(x, "nav2_controller");
checkMacro(pc, 0, 0, 0, 0, 1, true);
checkMacro(pc, 0, 0, 1, 0, 1, true);
checkMacro(pc, 0, 0, 0, 1, 1, true);
checkMacro(pc, 0, 0, 1, 0, 11, true);
checkMacro(pc, 0, 0, 0, 1, 11, true);
checkMacro(pc, 0, 0, 0, 0, 11, false);
checkMacro(pc, 0, 0, 0, 0, 0, 0, 1, true);
checkMacro(pc, 0, 0, 0, 1, 0, 0, 1, true);
checkMacro(pc, 0, 0, 0, 0, 1, 0, 1, true);
checkMacro(pc, 0, 0, 0, 1, 0, 0, 11, true);
checkMacro(pc, 0, 0, 0, 0, 1, 0, 11, true);
checkMacro(pc, 0, 0, 0, 0, 0, 0, 11, false);
}

TEST(RotationProgressChecker, rotation_progress_checker_reset)
{
auto x = std::make_shared<TestLifecycleNode>("rotation_progress_checker");

RotationProgressChecker * rpc = new RotationProgressChecker;
rpc->reset();
delete rpc;
EXPECT_TRUE(true);
}

TEST(RotationProgressChecker, unit_tests)
{
auto x = std::make_shared<TestLifecycleNode>("rotation_progress_checker");

RotationProgressChecker rpc;
rpc.initialize(x, "nav2_controller");

// 1s no movement
checkMacro(rpc, 0, 0, 0, 0, 0, 0, 1, true);
// 1s translation
checkMacro(rpc, 0, 0, 0, 1, 0, 0, 1, true);
checkMacro(rpc, 0, 0, 0, 0, 1, 0, 1, true);
// 1s rotation
checkMacro(rpc, 0, 0, 0, 0, 0, 1, 11, true);
checkMacro(rpc, 0, 0, 0, 0, 0, -1, 11, true);
// 11s translation
checkMacro(rpc, 0, 0, 0, 1, 0, 0, 11, true);
checkMacro(rpc, 0, 0, 0, 0, 1, 0, 11, true);
// 11s rotation
checkMacro(rpc, 0, 0, 0, 0, 0, 1, 11, true);
checkMacro(rpc, 0, 0, 0, 0, 0, -1, 11, true);
// 11s no movement
checkMacro(rpc, 0, 0, 0, 0, 0, 0, 11, false);

doisyg marked this conversation as resolved.
Show resolved Hide resolved

}

int main(int argc, char ** argv)
Expand Down