ros2_control - galactic
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/visibility_control.h"
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 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
35 Trajectory();
36
37 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
38 explicit Trajectory(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
39
40 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
41 explicit Trajectory(
42 const rclcpp::Time & current_time,
43 const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
44 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
45
50 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
52 const rclcpp::Time & current_time,
53 const trajectory_msgs::msg::JointTrajectoryPoint & current_point);
54
55 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
56 void update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
57
60
73 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
74 bool sample(
75 const rclcpp::Time & sample_time, trajectory_msgs::msg::JointTrajectoryPoint & expected_state,
76 TrajectoryPointConstIter & start_segment_itr, TrajectoryPointConstIter & end_segment_itr);
77
97 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
99 const rclcpp::Time & time_a, const trajectory_msgs::msg::JointTrajectoryPoint & state_a,
100 const rclcpp::Time & time_b, const trajectory_msgs::msg::JointTrajectoryPoint & state_b,
101 const rclcpp::Time & sample_time, trajectory_msgs::msg::JointTrajectoryPoint & output);
102
103 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
104 TrajectoryPointConstIter begin() const;
105
106 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
107 TrajectoryPointConstIter end() const;
108
109 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
110 rclcpp::Time time_from_start() const;
111
112 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
113 bool has_trajectory_msg() const;
114
115 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
116 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> get_trajectory_msg() const
117 {
118 return trajectory_msg_;
119 }
120
121 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
122 rclcpp::Time get_trajectory_start_time() const { return trajectory_start_time_; }
123
124 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
125 bool is_sampled_already() const { return sampled_already_; }
126
127private:
128 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
129 rclcpp::Time trajectory_start_time_;
130
131 rclcpp::Time time_before_traj_msg_;
132 trajectory_msgs::msg::JointTrajectoryPoint state_before_traj_msg_;
133
134 bool sampled_already_ = false;
135};
136
142template <class T>
143inline std::vector<size_t> mapping(const T & t1, const T & t2)
144{
145 // t1 must be a subset of t2
146 if (t1.size() > t2.size())
147 {
148 return std::vector<size_t>();
149 }
150
151 std::vector<size_t> mapping_vector(t1.size()); // Return value
152 for (auto t1_it = t1.begin(); t1_it != t1.end(); ++t1_it)
153 {
154 auto t2_it = std::find(t2.begin(), t2.end(), *t1_it);
155 if (t2.end() == t2_it)
156 {
157 return std::vector<size_t>();
158 }
159 else
160 {
161 const size_t t1_dist = std::distance(t1.begin(), t1_it);
162 const size_t t2_dist = std::distance(t2.begin(), t2_it);
163 mapping_vector[t1_dist] = t2_dist;
164 }
165 }
166 return mapping_vector;
167}
168
169} // namespace joint_trajectory_controller
170
171#endif // JOINT_TRAJECTORY_CONTROLLER__TRAJECTORY_HPP_
Definition trajectory.hpp:32
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool sample(const rclcpp::Time &sample_time, trajectory_msgs::msg::JointTrajectoryPoint &expected_state, TrajectoryPointConstIter &start_segment_itr, TrajectoryPointConstIter &end_segment_itr)
Definition trajectory.cpp:60
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:144
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void set_point_before_trajectory_msg(const rclcpp::Time &current_time, const trajectory_msgs::msg::JointTrajectoryPoint &current_point)
Definition trajectory.cpp:45
Definition joint_trajectory_controller.hpp:58
std::vector< size_t > mapping(const T &t1, const T &t2)
Definition trajectory.hpp:143