30 #ifndef JOINT_TRAJECTORY_CONTROLLER_TOLERANCES_H 31 #define JOINT_TRAJECTORY_CONTROLLER_TOLERANCES_H 43 #include <control_msgs/FollowJointTrajectoryAction.h> 53 template<
class Scalar>
57 Scalar velocity_tolerance = static_cast<Scalar>(0.0),
58 Scalar acceleration_tolerance = static_cast<Scalar>(0.0))
72 template<
class Scalar>
76 : state_tolerance(size, static_cast<Scalar>(0.0)),
77 goal_state_tolerance(size, static_cast<Scalar>(0.0)),
78 goal_time_tolerance(static_cast<Scalar>(0.0))
94 template<
class Scalar>
98 : state_tolerance(static_cast<Scalar>(0.0)),
99 goal_state_tolerance(static_cast<Scalar>(0.0)),
100 goal_time_tolerance(static_cast<Scalar>(0.0))
119 template <
class State>
122 bool show_errors =
false)
124 const unsigned int n_joints = state_tolerance.size();
127 assert(n_joints == state_error.position.size());
128 assert(n_joints == state_error.velocity.size());
129 assert(n_joints == state_error.acceleration.size());
131 for (
unsigned int i = 0; i < n_joints; ++i)
135 const bool is_valid = !(tol.
position > 0.0 && abs(state_error.position[i]) > tol.
position) &&
147 " Position Tolerance: " << tol.
position);
150 " Velocity Tolerance: " << tol.
velocity);
167 template <
class State>
170 bool show_errors =
false)
175 const bool is_valid = !(state_tolerance.
position > 0.0 && abs(state_error.position[0]) > state_tolerance.
position) &&
176 !(state_tolerance.
velocity > 0.0 && abs(state_error.velocity[0]) > state_tolerance.
velocity) &&
185 if (state_tolerance.
position > 0.0 && abs(state_error.position[0]) > state_tolerance.
position)
187 " Position Tolerance: " << state_tolerance.
position);
188 if (state_tolerance.
velocity > 0.0 && abs(state_error.velocity[0]) > state_tolerance.
velocity)
190 " Velocity Tolerance: " << state_tolerance.
velocity);
193 " Acceleration Tolerance: " << state_tolerance.
acceleration);
211 template<
class Scalar>
214 if (tol_msg.position > 0.0) {tols.
position =
static_cast<Scalar
>(tol_msg.position);}
215 else if (tol_msg.position < 0.0) {tols.
position =
static_cast<Scalar
>(0.0);}
217 if (tol_msg.velocity > 0.0) {tols.
velocity =
static_cast<Scalar
>(tol_msg.velocity);}
218 else if (tol_msg.velocity < 0.0) {tols.
velocity =
static_cast<Scalar
>(0.0);}
220 if (tol_msg.acceleration > 0.0) {tols.
acceleration =
static_cast<Scalar
>(tol_msg.acceleration);}
221 else if (tol_msg.acceleration < 0.0) {tols.
acceleration =
static_cast<Scalar
>(0.0);}
231 template<
class Scalar>
233 const std::vector<std::string>& joint_names,
241 typedef typename std::vector<std::string>::const_iterator StringConstIterator;
242 typedef typename std::vector<control_msgs::JointTolerance>::const_iterator TolMsgConstIterator;
244 for (StringConstIterator names_it = joint_names.begin(); names_it != joint_names.end(); ++names_it)
246 const typename std::vector<std::string>::size_type
id = std::distance(joint_names.begin(), names_it);
249 const std::vector<control_msgs::JointTolerance>& state_tol = goal.path_tolerance;
250 for(TolMsgConstIterator state_tol_it = state_tol.begin(); state_tol_it != state_tol.end(); ++state_tol_it)
256 const std::vector<control_msgs::JointTolerance>& g_state_tol = goal.goal_tolerance;
257 for(TolMsgConstIterator g_state_tol_it = g_state_tol.begin(); g_state_tol_it != g_state_tol.end(); ++g_state_tol_it)
264 const ros::Duration& goal_time_tolerance = goal.goal_time_tolerance;
290 template<
class Scalar>
292 const std::vector<std::string>& joint_names)
294 const unsigned int n_joints = joint_names.size();
298 double stopped_velocity_tolerance;
299 nh.
param(
"stopped_velocity_tolerance", stopped_velocity_tolerance, 0.01);
303 for (
unsigned int i = 0; i < n_joints; ++i)
318 #endif // header guard std::vector< StateTolerances< Scalar > > state_tolerance
Scalar goal_time_tolerance
StateTolerances< Scalar > state_tolerance
#define ROS_ERROR_STREAM_NAMED(name, args)
void updateStateTolerances(const control_msgs::JointTolerance &tol_msg, StateTolerances< Scalar > &tols)
Update data in tols from data in msg_tol.
void updateSegmentTolerances(const control_msgs::FollowJointTrajectoryGoal &goal, const std::vector< std::string > &joint_names, SegmentTolerances< Scalar > &tols)
Update data in tols from data in goal.
SegmentTolerancesPerJoint()
StateTolerances(Scalar position_tolerance=static_cast< Scalar >(0.0), Scalar velocity_tolerance=static_cast< Scalar >(0.0), Scalar acceleration_tolerance=static_cast< Scalar >(0.0))
bool checkStateTolerancePerJoint(const State &state_error, const StateTolerances< typename State::Scalar > &state_tolerance, bool show_errors=false)
Scalar goal_time_tolerance
SegmentTolerances(const typename std::vector< StateTolerances< Scalar > >::size_type &size=0)
StateTolerances< Scalar > goal_state_tolerance
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Trajectory state tolerances for position, velocity and acceleration variables.
SegmentTolerances< Scalar > getSegmentTolerances(const ros::NodeHandle &nh, const std::vector< std::string > &joint_names)
Populate trajectory segment tolerances from data in the ROS parameter server.
bool checkStateTolerance(const State &state_error, const std::vector< StateTolerances< typename State::Scalar > > &state_tolerance, bool show_errors=false)
Trajectory segment tolerances per Joint.
std::vector< StateTolerances< Scalar > > goal_state_tolerance
Trajectory segment tolerances.