forked from ros-navigation/navigation2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathsimple_progress_checker.cpp
121 lines (103 loc) · 4.06 KB
/
simple_progress_checker.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
// Copyright (c) 2019 Intel Corporation
//
// 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/simple_progress_checker.hpp"
#include <cmath>
#include <string>
#include <memory>
#include <vector>
#include "nav2_core/exceptions.hpp"
#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
{
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)
{
plugin_name_ = plugin_name;
auto node = parent.lock();
clock_ = node->get_clock();
nav2_util::declare_parameter_if_not_declared(
node, plugin_name + ".required_movement_radius", rclcpp::ParameterValue(0.5));
nav2_util::declare_parameter_if_not_declared(
node, plugin_name + ".movement_time_allowance", rclcpp::ParameterValue(10.0));
// Scale is set to 0 by default, so if it was not set otherwise, set to 0
node->get_parameter_or(plugin_name + ".required_movement_radius", radius_, 0.5);
double time_allowance_param = 0.0;
node->get_parameter_or(plugin_name + ".movement_time_allowance", time_allowance_param, 10.0);
time_allowance_ = rclcpp::Duration::from_seconds(time_allowance_param);
// Add callback for dynamic parameters
dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(&SimpleProgressChecker::dynamicParametersCallback, this, _1));
}
bool SimpleProgressChecker::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_) || (is_robot_moved_enough(current_pose2d))) {
reset_baseline_pose(current_pose2d);
return true;
}
return !((clock_->now() - baseline_time_) > time_allowance_);
}
void SimpleProgressChecker::reset()
{
baseline_pose_set_ = false;
}
void SimpleProgressChecker::reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose)
{
baseline_pose_ = pose;
baseline_time_ = clock_->now();
baseline_pose_set_ = true;
}
bool SimpleProgressChecker::is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose)
{
return pose_distance(pose, baseline_pose_) > radius_;
}
static double pose_distance(
const geometry_msgs::msg::Pose2D & pose1,
const geometry_msgs::msg::Pose2D & pose2)
{
double dx = pose1.x - pose2.x;
double dy = pose1.y - pose2.y;
return std::hypot(dx, dy);
}
rcl_interfaces::msg::SetParametersResult
SimpleProgressChecker::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_radius") {
radius_ = parameter.as_double();
} else if (name == plugin_name_ + ".movement_time_allowance") {
time_allowance_ = rclcpp::Duration::from_seconds(parameter.as_double());
}
}
}
result.successful = true;
return result;
}
} // namespace nav2_controller
PLUGINLIB_EXPORT_CLASS(nav2_controller::SimpleProgressChecker, nav2_core::ProgressChecker)