ros2_control - rolling
|
Classes | |
class | JointTrajectoryController |
struct | StateTolerances |
Trajectory state tolerances for position, velocity and acceleration variables. More... | |
struct | SegmentTolerances |
Trajectory segment tolerances. More... | |
class | Trajectory |
Functions | |
SegmentTolerances | get_segment_tolerances (rclcpp::Logger &jtc_logger, const Params ¶ms) |
Populate trajectory segment tolerances using data from the ROS node. More... | |
double | resolve_tolerance_source (const double default_value, const double goal_value) |
SegmentTolerances | get_segment_tolerances (rclcpp::Logger &jtc_logger, const SegmentTolerances &default_tolerances, const control_msgs::action::FollowJointTrajectory::Goal &goal, const std::vector< std::string > &joints) |
Populate trajectory segment tolerances using data from an action goal. More... | |
bool | check_state_tolerance_per_joint (const trajectory_msgs::msg::JointTrajectoryPoint &state_error, size_t joint_idx, const StateTolerances &state_tolerance, bool show_errors=false) |
template<class T > | |
std::vector< size_t > | mapping (const T &t1, const T &t2) |
void | wraparound_joint (std::vector< double > ¤t_position, const std::vector< double > next_position, const std::vector< bool > &joints_angle_wraparound) |
tl::expected< void, std::string > | command_interface_type_combinations (rclcpp::Parameter const ¶meter) |
tl::expected< void, std::string > | state_interface_type_combinations (rclcpp::Parameter const ¶meter) |
|
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 | ( | rclcpp::Logger & | jtc_logger, |
const Params & | params | ||
) |
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:
jtc_logger | The logger to use for output |
params | The ROS Parameters |
SegmentTolerances joint_trajectory_controller::get_segment_tolerances | ( | rclcpp::Logger & | jtc_logger, |
const SegmentTolerances & | default_tolerances, | ||
const control_msgs::action::FollowJointTrajectory::Goal & | goal, | ||
const std::vector< std::string > & | joints | ||
) |
Populate trajectory segment tolerances using data from an action goal.
jtc_logger | The logger to use for output |
default_tolerances | The default tolerances to use if the action goal does not specify any. |
goal | The new action goal |
joints | The joints configured by ROS parameters |
|
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}"
. void joint_trajectory_controller::wraparound_joint | ( | std::vector< double > & | current_position, |
const std::vector< double > | next_position, | ||
const std::vector< bool > & | joints_angle_wraparound | ||
) |
current_position | The current position given from the controller, which will be adapted. |
next_position | Next position from which to compute the wraparound offset, i.e., the first trajectory point |
joints_angle_wraparound | Vector of boolean where true value corresponds to a joint that wrap around (ie. is continuous). |