35 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
38 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
39 explicit Trajectory(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
41 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
43 const rclcpp::Time & current_time,
44 const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
45 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
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>());
61 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
62 void update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
98 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
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);
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);
132 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
133 TrajectoryPointConstIter begin()
const;
135 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
136 TrajectoryPointConstIter end()
const;
138 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
139 rclcpp::Time time_from_start()
const;
141 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
142 bool has_trajectory_msg()
const;
144 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
145 bool has_nontrivial_msg()
const;
147 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
148 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> get_trajectory_msg()
const
150 return trajectory_msg_;
153 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
154 bool is_sampled_already()
const {
return sampled_already_; }
161 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
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);
170 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
171 rclcpp::Time trajectory_start_time_;
173 rclcpp::Time time_before_traj_msg_;
174 trajectory_msgs::msg::JointTrajectoryPoint state_before_traj_msg_;
176 bool sampled_already_ =
false;
177 size_t last_sample_idx_ = 0;
186inline std::vector<size_t>
mapping(
const T & t1,
const T & t2)
189 if (t1.size() > t2.size())
191 return std::vector<size_t>();
194 std::vector<size_t> mapping_vector(t1.size());
195 for (
auto t1_it = t1.begin(); t1_it != t1.end(); ++t1_it)
197 auto t2_it = std::find(t2.begin(), t2.end(), *t1_it);
198 if (t2.end() == t2_it)
200 return std::vector<size_t>();
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;
209 return mapping_vector;
220 std::vector<double> & current_position,
const std::vector<double> next_position,
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 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