ros2_control - rolling
Classes | Typedefs | Functions
joint_trajectory_controller Namespace Reference

Classes

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

Typedefs

using TrajectoryPointIter = std::vector< trajectory_msgs::msg::JointTrajectoryPoint >::iterator
 
using TrajectoryPointConstIter = std::vector< trajectory_msgs::msg::JointTrajectoryPoint >::const_iterator
 

Functions

SegmentTolerances get_segment_tolerances (rclcpp::Logger &jtc_logger, const Params &params)
 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 > &current_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 &parameter)
 
tl::expected< void, std::string > state_interface_type_combinations (rclcpp::Parameter const &parameter)
 

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,
size_t  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() [1/2]

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:

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
jtc_loggerThe logger to use for output
paramsThe ROS Parameters
Returns
Trajectory segment tolerances.

◆ get_segment_tolerances() [2/2]

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.

Parameters
jtc_loggerThe logger to use for output
default_tolerancesThe default tolerances to use if the action goal does not specify any.
goalThe new action goal
jointsThe joints configured by ROS parameters
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}".

◆ wraparound_joint()

void joint_trajectory_controller::wraparound_joint ( std::vector< double > &  current_position,
const std::vector< double >  next_position,
const std::vector< bool > &  joints_angle_wraparound 
)
Parameters
current_positionThe current position given from the controller, which will be adapted.
next_positionNext position from which to compute the wraparound offset, i.e., the first trajectory point
joints_angle_wraparoundVector of boolean where true value corresponds to a joint that wrap around (ie. is continuous).