ros2_control - rolling
|
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, 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, const bool search_monotonically_increasing=true) |
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 |
JOINT_TRAJECTORY_CONTROLLER_PUBLIC size_t | last_sample_index () const |
Get the index of the segment start returned by the last sample() operation. More... | |
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 . |
|
inline |
Get the index of the segment start returned by the last sample()
operation.
As the trajectory is only accessed at monotonically increasing sampling times, this index is used to speed up the selection of relevant trajectory points.
bool joint_trajectory_controller::Trajectory::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 |
||
) |
Find the segment (made up of 2 points) and its expected state from the containing trajectory. Sampling trajectory at given sample_time
. If position in the end_segment_itr
is missing it will be deduced from provided velocity, or acceleration respectively. Deduction assumes that the provided velocity or acceleration have to be reached at the time defined in the segment.
This function by default assumes that sampling is only done at monotonically increasing sample_time
for any trajectory. That means, it will only search for a point matching the sample time after the point it has been called before. If this isn't desired, set search_monotonically_increasing
to false.
Specific case returns for start_segment_itr and end_segment_itr:
[in] | sample_time | Time at which trajectory will be sampled. |
[in] | interpolation_method | Specify whether splines, another method, or no interpolation at all. |
[out] | output_state | Calculated new at sample_time . |
[out] | start_segment_itr | Iterator to the start segment for given sample_time . See description above. |
[out] | end_segment_itr | Iterator to the end segment for given sample_time . See description above. |
[in] | search_monotonically_increasing | If set to true, the next sample call will start searching in the trajectory at the index of this call's result. |
void joint_trajectory_controller::Trajectory::set_point_before_trajectory_msg | ( | const rclcpp::Time & | current_time, |
const trajectory_msgs::msg::JointTrajectoryPoint & | current_point, | ||
const std::vector< bool > & | joints_angle_wraparound = std::vector<bool>() |
||
) |
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
joints_angle_wraparound | Vector of boolean where true value corresponds to a joint that wrap around (ie. is continuous). |