![]() |
ros2_control - galactic
|
Classes | |
class | JointTrajectoryController |
struct | SegmentTolerances |
Trajectory segment tolerances. More... | |
struct | StateTolerances |
Trajectory state tolerances for position, velocity and acceleration variables. More... | |
class | Trajectory |
Functions | |
SegmentTolerances | get_segment_tolerances (const rclcpp::Node &node, const std::vector< std::string > &joint_names) |
Populate trajectory segment tolerances using data from the ROS node. | |
bool | check_state_tolerance_per_joint (const trajectory_msgs::msg::JointTrajectoryPoint &state_error, int joint_idx, const StateTolerances &state_tolerance, bool show_errors=false) |
template<class T > | |
std::vector< size_t > | mapping (const T &t1, const T &t2) |
|
inline |
state_error | State error to check. |
joint_idx | Joint index for the state error |
state_tolerance | State tolerance of joint to check state_error against. |
show_errors | If the joint that violate its tolerance should be output to console. NOT REALTIME if true |
state_error
fulfills state_tolerance
. SegmentTolerances joint_trajectory_controller::get_segment_tolerances | ( | const rclcpp::Node & | node, |
const std::vector< std::string > & | joint_names | ||
) |
Populate trajectory segment tolerances using data from the ROS node.
It is assumed that the following parameter structure is followed on the provided LifecycleNode. Unspecified parameters will take the defaults shown in the comments:
node | LifecycleNode where the tolerances are specified. |
joint_names | Names of joints to look for in the parameter server for a tolerance specification. |
|
inline |
t1
indices (implicitly encoded in return vector indices) to t2
indices. If t1
is "{C, B}"
and t2
is "{A, B, C, D}"
, the associated mapping vector is "{2, 1}"
.