Maintain a sequence of waypoints and the time durations between these waypoints. More...
#include <robot_trajectory.h>
Public Member Functions | |
RobotTrajectory & | addPrefixWayPoint (const moveit::core::RobotState &state, double dt) |
RobotTrajectory & | addPrefixWayPoint (const moveit::core::RobotStatePtr &state, double dt) |
RobotTrajectory & | addSuffixWayPoint (const moveit::core::RobotState &state, double dt) |
Add a point to the trajectory. More... | |
RobotTrajectory & | addSuffixWayPoint (const moveit::core::RobotStatePtr &state, double dt) |
Add a point to the trajectory. More... | |
RobotTrajectory & | append (const RobotTrajectory &source, double dt, size_t start_index=0, size_t end_index=std::numeric_limits< std::size_t >::max()) |
Add a specified part of a trajectory to the end of the current trajectory. The default (when start_index and end_index are omitted) is to add the whole trajectory. More... | |
RobotTrajectory & | clear () |
bool | empty () const |
void | findWayPointIndicesForDurationAfterStart (const double duration, int &before, int &after, double &blend) const |
Finds the waypoint indicies before and after a duration from start. More... | |
double | getAverageSegmentDuration () const |
double | getDuration () const |
const moveit::core::RobotState & | getFirstWayPoint () const |
moveit::core::RobotStatePtr & | getFirstWayPointPtr () |
const moveit::core::JointModelGroup * | getGroup () const |
const std::string & | getGroupName () const |
const moveit::core::RobotState & | getLastWayPoint () const |
moveit::core::RobotStatePtr & | getLastWayPointPtr () |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
void | getRobotTrajectoryMsg (moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const |
bool | getStateAtDurationFromStart (const double request_duration, moveit::core::RobotStatePtr &output_state) const |
Gets a robot state corresponding to a supplied duration from start for the trajectory, using linear time interpolation. More... | |
const moveit::core::RobotState & | getWayPoint (std::size_t index) const |
std::size_t | getWayPointCount () const |
double | getWayPointDurationFromPrevious (std::size_t index) const |
double | getWayPointDurationFromStart (std::size_t index) const |
Returns the duration after start that a waypoint will be reached. More... | |
double | getWaypointDurationFromStart (std::size_t index) const |
const std::deque< double > & | getWayPointDurations () const |
moveit::core::RobotStatePtr & | getWayPointPtr (std::size_t index) |
RobotTrajectory & | insertWayPoint (std::size_t index, const moveit::core::RobotState &state, double dt) |
RobotTrajectory & | insertWayPoint (std::size_t index, const moveit::core::RobotStatePtr &state, double dt) |
RobotTrajectory & | operator= (const RobotTrajectory &)=default |
RobotTrajectory & | reverse () |
RobotTrajectory (const moveit::core::RobotModelConstPtr &robot_model) | |
construct a trajectory for the whole robot More... | |
RobotTrajectory (const moveit::core::RobotModelConstPtr &robot_model, const moveit::core::JointModelGroup *group) | |
construct a trajectory for the JointModelGroup Only joints from the specified group will be considered in this trajectory, even though all waypoints still consist of full RobotStates (representing all joints). More... | |
RobotTrajectory (const moveit::core::RobotModelConstPtr &robot_model, const std::string &group) | |
construct a trajectory for the named JointModelGroup If group is an empty string, this is equivalent to the first constructor, otherwise it is equivalent to RobotTrajectory(robot_model, robot_model->getJointModelGroup(group)) . More... | |
RobotTrajectory (const RobotTrajectory &other, bool deepcopy=false) | |
Copy constructor allowing a shallow or deep copy of waypoints. More... | |
RobotTrajectory & | setGroupName (const std::string &group_name) |
RobotTrajectory & | setRobotTrajectoryMsg (const moveit::core::RobotState &reference_state, const moveit_msgs::RobotState &state, const moveit_msgs::RobotTrajectory &trajectory) |
Copy the content of the trajectory message into this class. The trajectory message itself is not required to contain the values for all joints. For this reason a full starting state must be specified as reference (reference_state). Before use, the reference state is updated using state. Each point in the trajectory to be constructed internally is obtained by copying the reference state and overwriting the content from a trajectory point in trajectory. More... | |
RobotTrajectory & | setRobotTrajectoryMsg (const moveit::core::RobotState &reference_state, const moveit_msgs::RobotTrajectory &trajectory) |
Copy the content of the trajectory message into this class. The trajectory message itself is not required to contain the values for all joints. For this reason a full starting state must be specified as reference (reference_state). Each point in the trajectory to be constructed internally is obtained by copying the reference state and overwriting the content from a trajectory point in trajectory. More... | |
RobotTrajectory & | setRobotTrajectoryMsg (const moveit::core::RobotState &reference_state, const trajectory_msgs::JointTrajectory &trajectory) |
Copy the content of the trajectory message into this class. The trajectory message itself is not required to contain the values for all joints. For this reason a full starting state must be specified as reference (reference_state). Each point in the trajectory to be constructed internally is obtained by copying the reference state and overwriting the content from a trajectory point in trajectory. More... | |
RobotTrajectory & | setWayPointDurationFromPrevious (std::size_t index, double value) |
void | swap (robot_trajectory::RobotTrajectory &other) |
RobotTrajectory & | unwind () |
RobotTrajectory & | unwind (const moveit::core::RobotState &state) |
Private Attributes | |
std::deque< double > | duration_from_previous_ |
const moveit::core::JointModelGroup * | group_ |
moveit::core::RobotModelConstPtr | robot_model_ |
std::deque< moveit::core::RobotStatePtr > | waypoints_ |
Maintain a sequence of waypoints and the time durations between these waypoints.
Definition at line 84 of file robot_trajectory.h.
|
explicit |
construct a trajectory for the whole robot
Definition at line 77 of file robot_trajectory.cpp.
robot_trajectory::RobotTrajectory::RobotTrajectory | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
const std::string & | group | ||
) |
construct a trajectory for the named JointModelGroup If group is an empty string, this is equivalent to the first constructor, otherwise it is equivalent to RobotTrajectory(robot_model, robot_model->getJointModelGroup(group))
.
Definition at line 82 of file robot_trajectory.cpp.
robot_trajectory::RobotTrajectory::RobotTrajectory | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
const moveit::core::JointModelGroup * | group | ||
) |
construct a trajectory for the JointModelGroup Only joints from the specified group will be considered in this trajectory, even though all waypoints still consist of full RobotStates (representing all joints).
If group is nullptr this is equivalent to the first constructor.
Definition at line 87 of file robot_trajectory.cpp.
robot_trajectory::RobotTrajectory::RobotTrajectory | ( | const RobotTrajectory & | other, |
bool | deepcopy = false |
||
) |
Copy constructor allowing a shallow or deep copy of waypoints.
other | - RobotTrajectory to copy from |
deepcopy | - copy waypoints by value (true) or by pointer (false)? |
Definition at line 93 of file robot_trajectory.cpp.
|
inline |
Definition at line 223 of file robot_trajectory.h.
|
inline |
Definition at line 228 of file robot_trajectory.h.
|
inline |
Add a point to the trajectory.
state | - current robot state |
dt | - duration from previous |
Definition at line 205 of file robot_trajectory.h.
|
inline |
Add a point to the trajectory.
state | - current robot state |
dt | - duration from previous |
Definition at line 215 of file robot_trajectory.h.
RobotTrajectory & robot_trajectory::RobotTrajectory::append | ( | const RobotTrajectory & | source, |
double | dt, | ||
size_t | start_index = 0 , |
||
size_t | end_index = std::numeric_limits<std::size_t>::max() |
||
) |
Add a specified part of a trajectory to the end of the current trajectory. The default (when start_index
and end_index
are omitted) is to add the whole trajectory.
source | - the trajectory containing the part to append to the end of current trajectory |
dt | - time step between last traj point in current traj and first traj point of append traj |
start_index | - index of first traj point of the part to append from the source traj, the default is to add from the start of the source traj |
end_index | - index of last traj point of the part to append from the source traj, the default is to add until the end of the source traj |
Definition at line 135 of file robot_trajectory.cpp.
|
inline |
Definition at line 264 of file robot_trajectory.h.
|
inline |
Definition at line 195 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::findWayPointIndicesForDurationAfterStart | ( | const double | duration, |
int & | before, | ||
int & | after, | ||
double & | blend | ||
) | const |
Finds the waypoint indicies before and after a duration from start.
duration | The duration from start. |
before | The waypoint index before the supplied duration. |
after | The waypoint index after (or equal to) the supplied duration. |
blend | The progress (0 to 1) between the two waypoints, based on time (not based on joint distances). |
Definition at line 474 of file robot_trajectory.cpp.
double robot_trajectory::RobotTrajectory::getAverageSegmentDuration | ( | ) | const |
Definition at line 119 of file robot_trajectory.cpp.
double robot_trajectory::RobotTrajectory::getDuration | ( | ) | const |
Definition at line 114 of file robot_trajectory.cpp.
|
inline |
Definition at line 146 of file robot_trajectory.h.
|
inline |
Definition at line 161 of file robot_trajectory.h.
|
inline |
Definition at line 118 of file robot_trajectory.h.
const std::string & robot_trajectory::RobotTrajectory::getGroupName | ( | ) | const |
Definition at line 106 of file robot_trajectory.cpp.
|
inline |
Definition at line 141 of file robot_trajectory.h.
|
inline |
Definition at line 156 of file robot_trajectory.h.
|
inline |
Definition at line 113 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::getRobotTrajectoryMsg | ( | moveit_msgs::RobotTrajectory & | trajectory, |
const std::vector< std::string > & | joint_filter = std::vector<std::string>() |
||
) | const |
Definition at line 255 of file robot_trajectory.cpp.
bool robot_trajectory::RobotTrajectory::getStateAtDurationFromStart | ( | const double | request_duration, |
moveit::core::RobotStatePtr & | output_state | ||
) | const |
Gets a robot state corresponding to a supplied duration from start for the trajectory, using linear time interpolation.
request_duration | The duration from start. |
output_state | The resulting robot state. |
Definition at line 523 of file robot_trajectory.cpp.
|
inline |
Definition at line 136 of file robot_trajectory.h.
|
inline |
Definition at line 131 of file robot_trajectory.h.
|
inline |
Definition at line 179 of file robot_trajectory.h.
double robot_trajectory::RobotTrajectory::getWayPointDurationFromStart | ( | std::size_t | index | ) | const |
Returns the duration after start that a waypoint will be reached.
index | The waypoint index. |
Definition at line 505 of file robot_trajectory.cpp.
double robot_trajectory::RobotTrajectory::getWaypointDurationFromStart | ( | std::size_t | index | ) | const |
Definition at line 518 of file robot_trajectory.cpp.
|
inline |
Definition at line 166 of file robot_trajectory.h.
|
inline |
Definition at line 151 of file robot_trajectory.h.
|
inline |
Definition at line 236 of file robot_trajectory.h.
|
inline |
Definition at line 241 of file robot_trajectory.h.
|
default |
Assignment operator, performing a shallow copy, i.e. copying waypoints by pointer
RobotTrajectory & robot_trajectory::RobotTrajectory::reverse | ( | ) |
Definition at line 152 of file robot_trajectory.cpp.
|
inline |
Definition at line 125 of file robot_trajectory.h.
RobotTrajectory & robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg | ( | const moveit::core::RobotState & | reference_state, |
const moveit_msgs::RobotState & | state, | ||
const moveit_msgs::RobotTrajectory & | trajectory | ||
) |
Copy the content of the trajectory message into this class. The trajectory message itself is not required to contain the values for all joints. For this reason a full starting state must be specified as reference (reference_state). Before use, the reference state is updated using state. Each point in the trajectory to be constructed internally is obtained by copying the reference state and overwriting the content from a trajectory point in trajectory.
Definition at line 465 of file robot_trajectory.cpp.
RobotTrajectory & robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg | ( | const moveit::core::RobotState & | reference_state, |
const moveit_msgs::RobotTrajectory & | trajectory | ||
) |
Copy the content of the trajectory message into this class. The trajectory message itself is not required to contain the values for all joints. For this reason a full starting state must be specified as reference (reference_state). Each point in the trajectory to be constructed internally is obtained by copying the reference state and overwriting the content from a trajectory point in trajectory.
Definition at line 417 of file robot_trajectory.cpp.
RobotTrajectory & robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg | ( | const moveit::core::RobotState & | reference_state, |
const trajectory_msgs::JointTrajectory & | trajectory | ||
) |
Copy the content of the trajectory message into this class. The trajectory message itself is not required to contain the values for all joints. For this reason a full starting state must be specified as reference (reference_state). Each point in the trajectory to be constructed internally is obtained by copying the reference state and overwriting the content from a trajectory point in trajectory.
Definition at line 389 of file robot_trajectory.cpp.
|
inline |
Definition at line 187 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::swap | ( | robot_trajectory::RobotTrajectory & | other | ) |
Definition at line 127 of file robot_trajectory.cpp.
RobotTrajectory & robot_trajectory::RobotTrajectory::unwind | ( | ) |
Definition at line 170 of file robot_trajectory.cpp.
RobotTrajectory & robot_trajectory::RobotTrajectory::unwind | ( | const moveit::core::RobotState & | state | ) |
Definition at line 207 of file robot_trajectory.cpp.
|
private |
Definition at line 333 of file robot_trajectory.h.
|
private |
Definition at line 331 of file robot_trajectory.h.
|
private |
Definition at line 330 of file robot_trajectory.h.
|
private |
Definition at line 332 of file robot_trajectory.h.