36 explicit Trajectory(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_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);
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>());
56 void update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
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);
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);
129 TrajectoryPointConstIter begin()
const;
131 TrajectoryPointConstIter end()
const;
133 rclcpp::Time time_from_start()
const;
135 bool has_trajectory_msg()
const;
137 bool has_nontrivial_msg()
const;
139 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> get_trajectory_msg()
const
141 return trajectory_msg_;
144 bool is_sampled_already()
const {
return sampled_already_; }
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);
159 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
160 rclcpp::Time trajectory_start_time_;
162 rclcpp::Time time_before_traj_msg_;
163 trajectory_msgs::msg::JointTrajectoryPoint state_before_traj_msg_;
165 bool sampled_already_ =
false;
166 size_t last_sample_idx_ = 0;
175inline std::vector<size_t>
mapping(
const T & t1,
const T & t2)
178 if (t1.size() > t2.size())
180 return std::vector<size_t>();
183 std::vector<size_t> mapping_vector(t1.size());
184 for (
auto t1_it = t1.begin(); t1_it != t1.end(); ++t1_it)
186 auto t2_it = std::find(t2.begin(), t2.end(), *t1_it);
187 if (t2.end() == t2_it)
189 return std::vector<size_t>();
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;
198 return mapping_vector;
209 std::vector<double> & current_position,
const std::vector<double> next_position,
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
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 ¤t_time, const trajectory_msgs::msg::JointTrajectoryPoint ¤t_point, const std::vector< bool > &joints_angle_wraparound=std::vector< bool >())
Definition trajectory.cpp:45
void wraparound_joint(std::vector< double > ¤t_position, const std::vector< double > next_position, const std::vector< bool > &joints_angle_wraparound)
Definition trajectory.cpp:59