#include <cassert>#include <cmath>#include <string>#include <vector>#include <ros/node_handle.h>#include <control_msgs/FollowJointTrajectoryAction.h>

Go to the source code of this file.
Classes | |
| struct | joint_trajectory_controller::SegmentTolerances< Scalar > |
| Trajectory segment tolerances. More... | |
| struct | joint_trajectory_controller::SegmentTolerancesPerJoint< Scalar > |
| Trajectory segment tolerances per Joint. More... | |
| struct | joint_trajectory_controller::StateTolerances< Scalar > |
| Trajectory state tolerances for position, velocity and acceleration variables. More... | |
Namespaces | |
| joint_trajectory_controller | |
Functions | |
| template<class State > | |
| bool | joint_trajectory_controller::checkStateTolerance (const State &state_error, const std::vector< StateTolerances< typename State::Scalar > > &state_tolerance, bool show_errors=false) |
| template<class State > | |
| bool | joint_trajectory_controller::checkStateTolerancePerJoint (const State &state_error, const StateTolerances< typename State::Scalar > &state_tolerance, bool show_errors=false) |
| template<class Scalar > | |
| SegmentTolerances< Scalar > | joint_trajectory_controller::getSegmentTolerances (const ros::NodeHandle &nh, const std::vector< std::string > &joint_names) |
| Populate trajectory segment tolerances from data in the ROS parameter server. More... | |
| template<class Scalar > | |
| void | joint_trajectory_controller::updateSegmentTolerances (const control_msgs::FollowJointTrajectoryGoal &goal, const std::vector< std::string > &joint_names, SegmentTolerances< Scalar > &tols) |
Update data in tols from data in goal. More... | |
| template<class Scalar > | |
| void | joint_trajectory_controller::updateStateTolerances (const control_msgs::JointTolerance &tol_msg, StateTolerances< Scalar > &tols) |
Update data in tols from data in msg_tol. More... | |