35 #include <dwb_core/trajectory_utils.hpp>
39 #include "tf2/LinearMath/Quaternion.hpp"
40 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
42 #include "rclcpp/duration.hpp"
44 #include "dwb_core/exceptions.hpp"
48 const geometry_msgs::msg::Pose & getClosestPose(
49 const dwb_msgs::msg::Trajectory2D & trajectory,
50 const double time_offset)
52 rclcpp::Duration goal_time = rclcpp::Duration::from_seconds(time_offset);
53 const unsigned int num_poses = trajectory.poses.size();
57 unsigned int closest_index = num_poses;
58 double closest_diff = 0.0;
59 for (
unsigned int i = 0; i < num_poses; ++i) {
60 double diff = std::fabs((rclcpp::Duration(trajectory.time_offsets[i]) - goal_time).seconds());
61 if (closest_index == num_poses || diff < closest_diff) {
65 if (goal_time < rclcpp::Duration(trajectory.time_offsets[i])) {
69 return trajectory.poses[closest_index];
72 geometry_msgs::msg::Pose projectPose(
73 const dwb_msgs::msg::Trajectory2D & trajectory,
74 const double time_offset)
76 rclcpp::Duration goal_time = rclcpp::Duration::from_seconds(time_offset);
77 const unsigned int num_poses = trajectory.poses.size();
81 if (goal_time <= (trajectory.time_offsets[0])) {
82 return trajectory.poses[0];
83 }
else if (goal_time >= rclcpp::Duration(trajectory.time_offsets[num_poses - 1])) {
84 return trajectory.poses[num_poses - 1];
87 for (
unsigned int i = 0; i < num_poses - 1; ++i) {
88 if (goal_time >= rclcpp::Duration(trajectory.time_offsets[i]) &&
89 goal_time < rclcpp::Duration(trajectory.time_offsets[i + 1]))
92 (rclcpp::Duration(trajectory.time_offsets[i + 1]) -
93 rclcpp::Duration(trajectory.time_offsets[i])).seconds();
94 double ratio = (goal_time - rclcpp::Duration(trajectory.time_offsets[i])).seconds() /
96 double inv_ratio = 1.0 - ratio;
97 const auto & pose_a = trajectory.poses[i];
98 const auto & pose_b = trajectory.poses[i + 1];
100 geometry_msgs::msg::Pose projected;
101 projected.position.x = pose_a.position.x * inv_ratio + pose_b.position.x * ratio;
102 projected.position.y = pose_a.position.y * inv_ratio + pose_b.position.y * ratio;
103 projected.position.z = pose_a.position.z * inv_ratio + pose_b.position.z * ratio;
106 tf2::Quaternion q1, q2;
107 tf2::fromMsg(pose_a.orientation, q1);
108 tf2::fromMsg(pose_b.orientation, q2);
109 projected.orientation = tf2::toMsg(q1.slerp(q2, ratio));
116 return trajectory.poses[num_poses - 1];