![]() |
ros2_control - galactic
|
Public Member Functions | |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC | Trajectory (std::shared_ptr< trajectory_msgs::msg::JointTrajectory > joint_trajectory) |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC | Trajectory (const rclcpp::Time ¤t_time, const trajectory_msgs::msg::JointTrajectoryPoint ¤t_point, std::shared_ptr< trajectory_msgs::msg::JointTrajectory > joint_trajectory) |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | set_point_before_trajectory_msg (const rclcpp::Time ¤t_time, const trajectory_msgs::msg::JointTrajectoryPoint ¤t_point) |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC void | update (std::shared_ptr< trajectory_msgs::msg::JointTrajectory > joint_trajectory) |
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) |
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) |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC TrajectoryPointConstIter | begin () const |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC TrajectoryPointConstIter | end () const |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC rclcpp::Time | time_from_start () const |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool | has_trajectory_msg () const |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC std::shared_ptr< trajectory_msgs::msg::JointTrajectory > | get_trajectory_msg () const |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC rclcpp::Time | get_trajectory_start_time () const |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC bool | is_sampled_already () const |
void joint_trajectory_controller::Trajectory::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 | ||
) |
Do interpolation between 2 states given a time in between their respective timestamps
The start and end states need not necessarily be specified all the way to the acceleration level:
If start and end states have different specifications (eg. start is position-only, end is position-velocity), the lowest common specification will be used (position-only in the example).
[in] | time_a | Time at which the segment state equals state_a . |
[in] | state_a | State at time_a . |
[in] | time_b | Time at which the segment state equals state_b . |
[in] | state_b | State at time time_b . |
[in] | sample_time | The time to sample, between time_a and time_b. |
[out] | output | The state at sample_time . |
bool joint_trajectory_controller::Trajectory::sample | ( | const rclcpp::Time & | sample_time, |
trajectory_msgs::msg::JointTrajectoryPoint & | expected_state, | ||
TrajectoryPointConstIter & | start_segment_itr, | ||
TrajectoryPointConstIter & | end_segment_itr | ||
) |
Find the segment (made up of 2 points) and its expected state from the containing trajectory. Specific case returns for start_segment_itr and end_segment_itr:
void joint_trajectory_controller::Trajectory::set_point_before_trajectory_msg | ( | const rclcpp::Time & | current_time, |
const trajectory_msgs::msg::JointTrajectoryPoint & | current_point | ||
) |
Set the point before the trajectory message is replaced/appended Example: if we receive a new trajectory message and it's first point is 0.5 seconds from the current one, we call this function to log the current state, then append/replace the current trajectory