34 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
37 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
38 explicit Trajectory(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
40 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
42 const rclcpp::Time & current_time,
43 const trajectory_msgs::msg::JointTrajectoryPoint & current_point,
44 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
50 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
52 const rclcpp::Time & current_time,
53 const trajectory_msgs::msg::JointTrajectoryPoint & current_point);
55 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
56 void update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_trajectory);
73 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
75 const rclcpp::Time & sample_time, trajectory_msgs::msg::JointTrajectoryPoint & expected_state,
76 TrajectoryPointConstIter & start_segment_itr, TrajectoryPointConstIter & end_segment_itr);
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);
103 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
104 TrajectoryPointConstIter begin()
const;
106 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
107 TrajectoryPointConstIter end()
const;
109 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
110 rclcpp::Time time_from_start()
const;
112 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
113 bool has_trajectory_msg()
const;
115 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
116 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> get_trajectory_msg()
const
118 return trajectory_msg_;
121 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
122 rclcpp::Time get_trajectory_start_time()
const {
return trajectory_start_time_; }
124 JOINT_TRAJECTORY_CONTROLLER_PUBLIC
125 bool is_sampled_already()
const {
return sampled_already_; }
128 std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg_;
129 rclcpp::Time trajectory_start_time_;
131 rclcpp::Time time_before_traj_msg_;
132 trajectory_msgs::msg::JointTrajectoryPoint state_before_traj_msg_;
134 bool sampled_already_ =
false;
143inline std::vector<size_t>
mapping(
const T & t1,
const T & t2)
146 if (t1.size() > t2.size())
148 return std::vector<size_t>();
151 std::vector<size_t> mapping_vector(t1.size());
152 for (
auto t1_it = t1.begin(); t1_it != t1.end(); ++t1_it)
154 auto t2_it = std::find(t2.begin(), t2.end(), *t1_it);
155 if (t2.end() == t2_it)
157 return std::vector<size_t>();
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;
166 return mapping_vector;
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