Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
ego_polar_coords.hpp
1 // Copyright (c) 2023 Alberto J. Tudela Roldán
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_GRACEFUL_CONTROLLER__EGO_POLAR_COORDS_HPP_
16 #define NAV2_GRACEFUL_CONTROLLER__EGO_POLAR_COORDS_HPP_
17 
18 #include <math.h>
19 
20 #include "angles/angles.h"
21 #include "geometry_msgs/msg/pose.hpp"
22 #include "tf2/utils.h"
23 #include "tf2/transform_datatypes.h"
24 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
25 
26 namespace nav2_graceful_controller
27 {
28 
34 {
35  float r; // Radial distance between the robot pose and the target pose.
36  float phi; // Orientation of target with respect to the line of sight
37  // from the robot to the target.
38  float delta; // Steering angle of the robot with respect to the line of sight.
39 
41  const float & r_in = 0.0,
42  const float & phi_in = 0.0,
43  const float & delta_in = 0.0)
44  : r(r_in), phi(phi_in), delta(delta_in) {}
45 
57  const geometry_msgs::msg::Pose & target,
58  const geometry_msgs::msg::Pose & current = geometry_msgs::msg::Pose(), bool backward = false)
59  {
60  // Compute the difference between the target and the current pose
61  float dX = target.position.x - current.position.x;
62  float dY = target.position.y - current.position.y;
63  // Compute the line of sight from the robot to the target
64  // Flip it if the robot is moving backwards
65  float line_of_sight = backward ? (std::atan2(-dY, dX) + M_PI) : std::atan2(-dY, dX);
66  // Compute the ego polar coordinates
67  r = sqrt(dX * dX + dY * dY);
68  phi = angles::normalize_angle(tf2::getYaw(target.orientation) + line_of_sight);
69  delta = angles::normalize_angle(tf2::getYaw(current.orientation) + line_of_sight);
70  }
71 };
72 
73 } // namespace nav2_graceful_controller
74 
75 #endif // NAV2_GRACEFUL_CONTROLLER__EGO_POLAR_COORDS_HPP_
Egocentric polar coordinates defined as the difference between the robot pose and the target pose rel...
EgocentricPolarCoordinates(const geometry_msgs::msg::Pose &target, const geometry_msgs::msg::Pose &current=geometry_msgs::msg::Pose(), bool backward=false)
Construct a new egocentric polar coordinates as the difference between the robot pose and the target ...