-
Notifications
You must be signed in to change notification settings - Fork 1.8k
Expand file tree
/
Copy pathpose_progress_checker.cpp
More file actions
144 lines (130 loc) · 4.69 KB
/
pose_progress_checker.cpp
File metadata and controls
144 lines (130 loc) · 4.69 KB
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
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
// 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/pose_progress_checker.hpp"
#include <cmath>
#include <string>
#include <memory>
#include <vector>
#include "angles/angles.h"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include "nav2_ros_common/node_utils.hpp"
#include "pluginlib/class_list_macros.hpp"
#include "tf2/utils.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
using rcl_interfaces::msg::ParameterType;
using std::placeholders::_1;
namespace nav2_controller
{
PoseProgressChecker::~PoseProgressChecker()
{
auto node = node_.lock();
if (post_set_params_handler_ && node) {
node->remove_post_set_parameters_callback(post_set_params_handler_.get());
}
post_set_params_handler_.reset();
if (on_set_params_handler_ && node) {
node->remove_on_set_parameters_callback(on_set_params_handler_.get());
}
on_set_params_handler_.reset();
}
void PoseProgressChecker::initialize(
const nav2::LifecycleNode::WeakPtr & parent,
const std::string & plugin_name)
{
plugin_name_ = plugin_name;
SimpleProgressChecker::initialize(parent, plugin_name);
node_ = parent;
auto node = node_.lock();
logger_ = node->get_logger();
required_movement_angle_ = node->declare_or_get_parameter(
plugin_name + ".required_movement_angle", 0.5);
// Add callback for dynamic parameters
post_set_params_handler_ = node->add_post_set_parameters_callback(
std::bind(
&PoseProgressChecker::updateParametersCallback,
this, std::placeholders::_1));
on_set_params_handler_ = node->add_on_set_parameters_callback(
std::bind(
&PoseProgressChecker::validateParameterUpdatesCallback,
this, std::placeholders::_1));
}
bool PoseProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose)
{
std::lock_guard<std::mutex> lock_reinit(mutex_);
// relies on short circuit evaluation to not call is_robot_moved_enough if
// baseline_pose is not set.
if (!baseline_pose_set_ || PoseProgressChecker::isRobotMovedEnough(current_pose.pose)) {
resetBaselinePose(current_pose.pose);
return true;
}
return clock_->now() - baseline_time_ <= time_allowance_;
}
bool PoseProgressChecker::isRobotMovedEnough(const geometry_msgs::msg::Pose & pose)
{
return pose_distance(pose, baseline_pose_) > radius_ ||
poseAngleDistance(pose, baseline_pose_) > required_movement_angle_;
}
double PoseProgressChecker::poseAngleDistance(
const geometry_msgs::msg::Pose & pose1,
const geometry_msgs::msg::Pose & pose2)
{
double theta1 = tf2::getYaw(pose1.orientation);
double theta2 = tf2::getYaw(pose2.orientation);
return std::abs(angles::shortest_angular_distance(theta1, theta2));
}
rcl_interfaces::msg::SetParametersResult
PoseProgressChecker::validateParameterUpdatesCallback(
const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
continue;
}
if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (parameter.as_double() < 0.0) {
RCLCPP_WARN(
logger_, "The value of parameter '%s' is incorrectly set to %f, "
"it should be >=0. Ignoring parameter update.",
param_name.c_str(), parameter.as_double());
result.successful = false;
}
}
}
return result;
}
void
PoseProgressChecker::updateParametersCallback(
const std::vector<rclcpp::Parameter> & parameters)
{
std::lock_guard<std::mutex> lock_reinit(mutex_);
for (const auto & parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
continue;
}
if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == plugin_name_ + ".required_movement_angle") {
required_movement_angle_ = parameter.as_double();
}
}
}
}
} // namespace nav2_controller
PLUGINLIB_EXPORT_CLASS(nav2_controller::PoseProgressChecker, nav2_core::ProgressChecker)