ros2_control - humble
Loading...
Searching...
No Matches
trajectory.hpp
1// Copyright 2017 Open Source Robotics Foundation, Inc.
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 JOINT_TRAJECTORY_CONTROLLER__TRAJECTORY_HPP_
16#define JOINT_TRAJECTORY_CONTROLLER__TRAJECTORY_HPP_
17
18#include <memory>
19#include <vector>
20
21#include "joint_trajectory_controller/interpolation_methods.hpp"
22#include "joint_trajectory_controller/visibility_control.h"
23#include "rclcpp/time.hpp"
24#include "trajectory_msgs/msg/joint_trajectory.hpp"
25#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
27{
28using TrajectoryPointIter = std::vector<trajectory_msgs::msg::JointTrajectoryPoint>::iterator;
29using TrajectoryPointConstIter =
30 std::vector<trajectory_msgs::msg::JointTrajectoryPoint>::const_iterator;
31
33{
34public:
35 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
36 Trajectory();
37
38 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
39 explicit Trajectory(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
40
41 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
42 explicit Trajectory(
43 const rclcpp::Time & current_time,
44 const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
45 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
46
55 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
57 const rclcpp::Time & current_time,
58 const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
59 const std::vector<bool> & joints_angle_wraparound = std::vector<bool>());
60
61 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
62 void update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
63
66
98 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
99 bool sample(
100 const rclcpp::Time & sample_time,
101 const interpolation_methods::InterpolationMethod interpolation_method,
102 trajectory_msgs::msg::JointTrajectoryPoint & output_state,
103 TrajectoryPointConstIter & start_segment_itr, TrajectoryPointConstIter & end_segment_itr);
104
126 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
128 const rclcpp::Time & time_a, const trajectory_msgs::msg::JointTrajectoryPoint & state_a,
129 const rclcpp::Time & time_b, const trajectory_msgs::msg::JointTrajectoryPoint & state_b,
130 const rclcpp::Time & sample_time, trajectory_msgs::msg::JointTrajectoryPoint & output);
131
132 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
133 TrajectoryPointConstIter begin() const;
134
135 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
136 TrajectoryPointConstIter end() const;
137
138 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
139 rclcpp::Time time_from_start() const;
140
141 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
142 bool has_trajectory_msg() const;
143
144 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
145 bool has_nontrivial_msg() const;
146
147 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
148 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> get_trajectory_msg() const
149 {
150 return trajectory_msg_;
151 }
152
153 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
154 bool is_sampled_already() const { return sampled_already_; }
155
157
161 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
162 size_t last_sample_index() const { return last_sample_idx_; }
163
164private:
165 void deduce_from_derivatives(
166 trajectory_msgs::msg::JointTrajectoryPoint & first_state,
167 trajectory_msgs::msg::JointTrajectoryPoint & second_state, const size_t dim,
168 const double delta_t);
169
170 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
171 rclcpp::Time trajectory_start_time_;
172
173 rclcpp::Time time_before_traj_msg_;
174 trajectory_msgs::msg::JointTrajectoryPoint state_before_traj_msg_;
175
176 bool sampled_already_ = false;
177 size_t last_sample_idx_ = 0;
178};
179
185template <class T>
186inline std::vector<size_t> mapping(const T & t1, const T & t2)
187{
188 // t1 must be a subset of t2
189 if (t1.size() > t2.size())
190 {
191 return std::vector<size_t>();
192 }
193
194 std::vector<size_t> mapping_vector(t1.size()); // Return value
195 for (auto t1_it = t1.begin(); t1_it != t1.end(); ++t1_it)
196 {
197 auto t2_it = std::find(t2.begin(), t2.end(), *t1_it);
198 if (t2.end() == t2_it)
199 {
200 return std::vector<size_t>();
201 }
202 else
203 {
204 const size_t t1_dist = static_cast<size_t>(std::distance(t1.begin(), t1_it));
205 const size_t t2_dist = static_cast<size_t>(std::distance(t2.begin(), t2_it));
206 mapping_vector[t1_dist] = t2_dist;
207 }
208 }
209 return mapping_vector;
210}
211
220 std::vector<double> & current_position, const std::vector<double> next_position,
221 const std::vector<bool> & joints_angle_wraparound);
222
223} // namespace joint_trajectory_controller
224
225#endif // JOINT_TRAJECTORY_CONTROLLER__TRAJECTORY_HPP_
Definition trajectory.hpp:33
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void interpolate_between_points(const rclcpp::Time &time_a, const trajectory_msgs::msg::JointTrajectoryPoint &state_a, const rclcpp::Time &time_b, const trajectory_msgs::msg::JointTrajectoryPoint &state_b, const rclcpp::Time &sample_time, trajectory_msgs::msg::JointTrajectoryPoint &output)
Definition trajectory.cpp:202
JOINT_TRAJECTORY_CONTROLLER_PUBLIC size_t last_sample_index() const
Get the index of the segment start returned by the last sample() operation.
Definition trajectory.hpp:162
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool sample(const rclcpp::Time &sample_time, const interpolation_methods::InterpolationMethod interpolation_method, trajectory_msgs::msg::JointTrajectoryPoint &output_state, TrajectoryPointConstIter &start_segment_itr, TrajectoryPointConstIter &end_segment_itr)
Definition trajectory.cpp:91
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void set_point_before_trajectory_msg(const rclcpp::Time &current_time, const trajectory_msgs::msg::JointTrajectoryPoint &current_point, const std::vector< bool > &joints_angle_wraparound=std::vector< bool >())
Definition trajectory.cpp:46
Definition interpolation_methods.hpp:24
void wraparound_joint(std::vector< double > &current_position, const std::vector< double > next_position, const std::vector< bool > &joints_angle_wraparound)
Definition trajectory.cpp:60
std::vector< size_t > mapping(const T &t1, const T &t2)
Definition trajectory.hpp:186