forked from ros-navigation/navigation2
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #9 from botsandus/AUTO-607_path_distance_for_pruning
AUTO-607 use path distance instead of euclidean distance for pruning path
- Loading branch information
Showing
14 changed files
with
408 additions
and
52 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
68 changes: 68 additions & 0 deletions
68
nav2_controller/include/nav2_controller/plugins/rotation_progress_checker.hpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,68 @@ | ||
// 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" | ||
#include "nav2_core/progress_checker.hpp" | ||
#include "geometry_msgs/msg/pose_stamped.hpp" | ||
#include "geometry_msgs/msg/pose2_d.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); | ||
|
||
static double pose_angle_distance(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_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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( | ||
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) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.