Namespaces | |
internal | |
Classes | |
class | HoldTrajectoryBuilder |
Builder creating a trajectory "simply" holding (without motion) the specified position. More... | |
struct | InitJointTrajectoryOptions |
Options used when initializing a joint trajectory from ROS message data. More... | |
class | JointTrajectoryController |
Controller for executing joint-space trajectories on a group of joints. More... | |
class | JointTrajectorySegment |
Class representing a multi-dimensional quintic spline segment with a start and end time. More... | |
struct | SegmentTolerances |
Trajectory segment tolerances. More... | |
struct | SegmentTolerancesPerJoint |
Trajectory segment tolerances per Joint. More... | |
struct | StateTolerances |
Trajectory state tolerances for position, velocity and acceleration variables. More... | |
class | StopTrajectoryBuilder |
Builder creating a trajectory stopping the robot. More... | |
class | TrajectoryBuilder |
Base class for classes used to construct diffent trajectory types. More... | |
Functions | |
template<class State > | |
bool | checkStateTolerance (const State &state_error, const std::vector< StateTolerances< typename State::Scalar > > &state_tolerance, bool show_errors=false) |
template<class State > | |
bool | checkStateTolerancePerJoint (const State &state_error, const StateTolerances< typename State::Scalar > &state_tolerance, bool show_errors=false) |
std::vector< trajectory_msgs::JointTrajectoryPoint >::const_iterator | findPoint (const trajectory_msgs::JointTrajectory &msg, const ros::Time &time) |
Find an iterator to the trajectory point with the greatest start time < time . More... | |
template<class Scalar > | |
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. More... | |
template<class Trajectory > | |
Trajectory | initJointTrajectory (const trajectory_msgs::JointTrajectory &msg, const ros::Time &time, const InitJointTrajectoryOptions< Trajectory > &options=InitJointTrajectoryOptions< Trajectory >()) |
Initialize a joint trajectory from ROS message data. More... | |
template<class Trajectory > | |
bool | isNotEmpty (typename Trajectory::value_type trajPerJoint) |
bool | isTimeStrictlyIncreasing (const trajectory_msgs::JointTrajectory &msg) |
bool | isValid (const trajectory_msgs::JointTrajectory &msg) |
bool | isValid (const trajectory_msgs::JointTrajectoryPoint &point, const unsigned int joint_dim) |
template<class Scalar > | |
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 . More... | |
template<class Scalar > | |
void | updateStateTolerances (const control_msgs::JointTolerance &tol_msg, StateTolerances< Scalar > &tols) |
Update data in tols from data in msg_tol . More... | |
template<class Scalar > | |
Scalar | wraparoundJointOffset (const Scalar &prev_position, const Scalar &next_position, const bool &angle_wraparound) |
|
inline |
state_error | State error to check. |
state_tolerance | State tolerances to check state_error against. |
show_errors | If the joints that violate their tolerances should be output to console. NOT REALTIME if true |
state_error
fulfills state_tolerance
. Definition at line 120 of file tolerances.h.
|
inline |
state_error | State error to check. |
state_tolerance | State tolerances 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
. Definition at line 168 of file tolerances.h.
|
inline |
Find an iterator to the trajectory point with the greatest start time < time
.
msg | Trajectory message. |
time | Time to search for in the range. |
time
. If all points occur at a time greater than time
, then the
points sequence end is returned.msg
have monotonically increasing times.Definition at line 151 of file joint_trajectory_msg_utils.h.
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.
It is assumed that the following parameter structure is followed on the provided NodeHandle. Unspecified parameters will take the defaults shown in the comments:
nh | NodeHandle where the tolerances are specified. |
joint_names | Names of joints to look for in the parameter server for a tolerance specification. |
Definition at line 291 of file tolerances.h.
Trajectory joint_trajectory_controller::initJointTrajectory | ( | const trajectory_msgs::JointTrajectory & | msg, |
const ros::Time & | time, | ||
const InitJointTrajectoryOptions< Trajectory > & | options = InitJointTrajectoryOptions<Trajectory>() |
||
) |
Initialize a joint trajectory from ROS message data.
msg | Trajectory message. |
time | Time from which data is to be extracted. All trajectory points in msg occurring after time will be extracted; or put otherwise, all points occurring at a time less or equal than time will be discarded. Set this value to zero to process all points in msg . |
options | Options that change how the trajectory gets initialized. |
The options parameter is optional. The meaning of its different members follows:
msg
; that is, keep the useful parts of current_trajectory
and msg
. If specified, the output trajectory will not only contain data in msg
occurring after time
, but will also contain data from current_trajectory
between time
and the start time of msg
(which might not be equal to time
).msg
. If specified, this function will return an empty trajectory when msg
contains joints that differ in number or names to joint_names
. If msg
contains the same joints as joint_names
, but in a different order, the resulting trajectory will be ordered according to joint_names
(and not msg
). If unspecified (empty), no checks will be performed against expected joints, and the resulting trajectory will preserve the joint ordering of msg
.current_trajectory
with msg
will not result in joints performing multiple turns at the transition. This parameter requires current_trajectory
to also be specified, otherwise it is ignored.rt_goal_handle
is also specified. It contains the default tolernaces to check when executing an action goal. If the action goal specifies tolerances (totally or partially), these values will take precedence over the defaults.msg
. If specified, the value of this variable should be the equivalent of the time
parameter, but expressed in the desired time base. If the current_trajectory
option is also specified, it must be expressed in other_time_base
. The typical usecase for this variable is when the current_trajectory
option is specified, and contains data in a different time base (eg. monotonically increasing) than msg
(eg. system-clock synchronized).msg
.Trajectory | Trajectory type. Should be a sequence container sorted by segment start time. Additionally, the contained segment type must implement a constructor with the following signature: Segment(const ros::Time& traj_start_time,
const trajectory_msgs::JointTrajectoryPoint& start_point,
const trajectory_msgs::JointTrajectoryPoint& end_point,
const std::vector<Scalar>& position_offset)
std::vector<Scalar> wraparoundOffset(const typename Segment::State& prev_state,
const typename Segment::State& next_state,
const std::vector<bool>& angle_wraparound)
|
try
block. Definition at line 204 of file init_joint_trajectory.h.
bool joint_trajectory_controller::isNotEmpty | ( | typename Trajectory::value_type | trajPerJoint | ) |
Definition at line 132 of file init_joint_trajectory.h.
|
inline |
msg | Trajectory message. |
Definition at line 119 of file joint_trajectory_msg_utils.h.
|
inline |
msg | Trajectory message. |
Definition at line 95 of file joint_trajectory_msg_utils.h.
|
inline |
point | Trajectory point message. |
joint_dim | Expected dimension of the position, velocity and acceleration fields. |
joint_dim
. Definition at line 83 of file joint_trajectory_msg_utils.h.
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
.
[in] | goal | Action goal data containing tolerance values tols will be updated with. |
[in] | joint_names | Names of joints in tols , with the same ordering. |
[out] | tols | Tolerances values to update. |
Definition at line 232 of file tolerances.h.
void joint_trajectory_controller::updateStateTolerances | ( | const control_msgs::JointTolerance & | tol_msg, |
StateTolerances< Scalar > & | tols | ||
) |
Update data in tols
from data in msg_tol
.
tol_msg
is positive, the corresponding values in tols
will be overritten.tol_msg
is negative, the corresponding values in tols
will be reset.tol_msg
is zero, the corresponding values in tols
is unchanged.[in] | tol_msg | Message containing tolerance values tols will be updated with. |
[out] | tols | Tolerances values to update. |
Definition at line 212 of file tolerances.h.
Scalar joint_trajectory_controller::wraparoundJointOffset | ( | const Scalar & | prev_position, |
const Scalar & | next_position, | ||
const bool & | angle_wraparound | ||
) |
prev_position | Previous position from which to compute the wraparound offset. |
next_position | Next position from which to compute the wraparound offset. |
angle_wraparound | Boolean where true value corresponds to a joint that wrap around (ie. is continuous). Offset will be computed only for this joint, otherwise it is set to zero. |
next_position
such that no multi-turns are performed when transitioning from prev_position
. Scalar | Scalar type. |
Definition at line 223 of file joint_trajectory_segment.h.