ros2_control - rolling
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 "rclcpp/time.hpp"
23#include "trajectory_msgs/msg/joint_trajectory.hpp"
24#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
26{
27using TrajectoryPointIter = std::vector<trajectory_msgs::msg::JointTrajectoryPoint>::iterator;
28using TrajectoryPointConstIter =
29 std::vector<trajectory_msgs::msg::JointTrajectoryPoint>::const_iterator;
30
32{
33public:
34 Trajectory();
35
36 explicit Trajectory(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
37
38 explicit Trajectory(
39 const rclcpp::Time & current_time,
40 const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
41 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
42
52 const rclcpp::Time & current_time,
53 const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
54 const std::vector<bool> & joints_angle_wraparound = std::vector<bool>());
55
56 void update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
57
60
96 bool sample(
97 const rclcpp::Time & sample_time,
98 const interpolation_methods::InterpolationMethod interpolation_method,
99 trajectory_msgs::msg::JointTrajectoryPoint & output_state,
100 TrajectoryPointConstIter & start_segment_itr, TrajectoryPointConstIter & end_segment_itr,
101 const bool search_monotonically_increasing = true);
102
125 const rclcpp::Time & time_a, const trajectory_msgs::msg::JointTrajectoryPoint & state_a,
126 const rclcpp::Time & time_b, const trajectory_msgs::msg::JointTrajectoryPoint & state_b,
127 const rclcpp::Time & sample_time, trajectory_msgs::msg::JointTrajectoryPoint & output);
128
129 TrajectoryPointConstIter begin() const;
130
131 TrajectoryPointConstIter end() const;
132
133 rclcpp::Time time_from_start() const;
134
135 bool has_trajectory_msg() const;
136
137 bool has_nontrivial_msg() const;
138
139 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> get_trajectory_msg() const
140 {
141 return trajectory_msg_;
142 }
143
144 bool is_sampled_already() const { return sampled_already_; }
145
147
151 size_t last_sample_index() const { return last_sample_idx_; }
152
153private:
154 void deduce_from_derivatives(
155 trajectory_msgs::msg::JointTrajectoryPoint & first_state,
156 trajectory_msgs::msg::JointTrajectoryPoint & second_state, const size_t dim,
157 const double delta_t);
158
159 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
160 rclcpp::Time trajectory_start_time_;
161
162 rclcpp::Time time_before_traj_msg_;
163 trajectory_msgs::msg::JointTrajectoryPoint state_before_traj_msg_;
164
165 bool sampled_already_ = false;
166 size_t last_sample_idx_ = 0;
167};
168
174template <class T>
175inline std::vector<size_t> mapping(const T & t1, const T & t2)
176{
177 // t1 must be a subset of t2
178 if (t1.size() > t2.size())
179 {
180 return std::vector<size_t>();
181 }
182
183 std::vector<size_t> mapping_vector(t1.size()); // Return value
184 for (auto t1_it = t1.begin(); t1_it != t1.end(); ++t1_it)
185 {
186 auto t2_it = std::find(t2.begin(), t2.end(), *t1_it);
187 if (t2.end() == t2_it)
188 {
189 return std::vector<size_t>();
190 }
191 else
192 {
193 const size_t t1_dist = static_cast<size_t>(std::distance(t1.begin(), t1_it));
194 const size_t t2_dist = static_cast<size_t>(std::distance(t2.begin(), t2_it));
195 mapping_vector[t1_dist] = t2_dist;
196 }
197 }
198 return mapping_vector;
199}
200
209 std::vector<double> & current_position, const std::vector<double> next_position,
210 const std::vector<bool> & joints_angle_wraparound);
211
212} // namespace joint_trajectory_controller
213
214#endif // JOINT_TRAJECTORY_CONTROLLER__TRAJECTORY_HPP_
Definition trajectory.hpp:32
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:205
size_t last_sample_index() const
Get the index of the segment start returned by the last sample() operation.
Definition trajectory.hpp:151
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, const bool search_monotonically_increasing=true)
Definition trajectory.cpp:90
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:45
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:59
std::vector< size_t > mapping(const T &t1, const T &t2)
Definition trajectory.hpp:175