ros2_control - galactic
Loading...
Searching...
No Matches
Classes | Typedefs | Functions
joint_trajectory_controller Namespace Reference

Classes

class  JointTrajectoryController
 
struct  SegmentTolerances
 Trajectory segment tolerances. More...
 
struct  StateTolerances
 Trajectory state tolerances for position, velocity and acceleration variables. More...
 
class  Trajectory
 

Typedefs

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
 
using TrajectoryPointIter = std::vector< trajectory_msgs::msg::JointTrajectoryPoint >::iterator
 
using TrajectoryPointConstIter = std::vector< trajectory_msgs::msg::JointTrajectoryPoint >::const_iterator
 

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)
 

Detailed Description

Author
Adolfo Rodriguez Tsouroukdissian

Function Documentation

◆ check_state_tolerance_per_joint()

bool joint_trajectory_controller::check_state_tolerance_per_joint ( const trajectory_msgs::msg::JointTrajectoryPoint &  state_error,
int  joint_idx,
const StateTolerances state_tolerance,
bool  show_errors = false 
)
inline
Parameters
state_errorState error to check.
joint_idxJoint index for the state error
state_toleranceState tolerance of joint to check state_error against.
show_errorsIf the joint that violate its tolerance should be output to console. NOT REALTIME if true
Returns
True if state_error fulfills state_tolerance.

◆ get_segment_tolerances()

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:

constraints:
goal_time: 1.0 # Defaults to zero
stopped_velocity_tolerance: 0.02 # Defaults to 0.01
foo_joint:
trajectory: 0.05 # Defaults to zero (ie. the tolerance is not enforced)
goal: 0.03 # Defaults to zero (ie. the tolerance is not enforced)
bar_joint:
goal: 0.01
Parameters
nodeLifecycleNode where the tolerances are specified.
joint_namesNames of joints to look for in the parameter server for a tolerance specification.
Returns
Trajectory segment tolerances.

◆ mapping()

template<class T >
std::vector< size_t > joint_trajectory_controller::mapping ( const T &  t1,
const T &  t2 
)
inline
Returns
The map between 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}".