|
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, const std::vector< bool > &joints_angle_wraparound=std::vector< bool >()) |
|
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, const interpolation_methods::InterpolationMethod interpolation_method, trajectory_msgs::msg::JointTrajectoryPoint &output_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 bool | has_nontrivial_msg () const |
|
JOINT_TRAJECTORY_CONTROLLER_PUBLIC std::shared_ptr< trajectory_msgs::msg::JointTrajectory > | get_trajectory_msg () 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 only positions are specified, linear interpolation will be used.
- If positions and velocities are specified, a cubic spline will be used.
- If positions, velocities and accelerations are specified, a quintic spline will be used.
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).
- Parameters
-
[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 . |