Maintain a sequence of waypoints and the time durations between these waypoints. More...
#include <robot_trajectory.h>
Public Member Functions | |
void | addPrefixWayPoint (const robot_state::RobotState &state, double dt) |
void | addPrefixWayPoint (const robot_state::RobotStatePtr &state, double dt) |
void | addSuffixWayPoint (const robot_state::RobotState &state, double dt) |
Add a point to the trajectory. | |
void | addSuffixWayPoint (const robot_state::RobotStatePtr &state, double dt) |
Add a point to the trajectory. | |
void | append (const RobotTrajectory &source, double dt) |
Add a trajectory to the end of the current trajectory. | |
void | 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. | |
double | getAverageSegmentDuration () const |
const robot_state::RobotState & | getFirstWayPoint () const |
robot_state::RobotStatePtr & | getFirstWayPointPtr () |
const robot_model::JointModelGroup * | getGroup () const |
const std::string & | getGroupName () const |
const robot_state::RobotState & | getLastWayPoint () const |
robot_state::RobotStatePtr & | getLastWayPointPtr () |
const robot_model::RobotModelConstPtr & | getRobotModel () const |
void | getRobotTrajectoryMsg (moveit_msgs::RobotTrajectory &trajectory) const |
bool | getStateAtDurationFromStart (const double request_duration, robot_state::RobotStatePtr &output_state) const |
Gets a robot state corresponding to a supplied duration from start for the trajectory, using linear time interpolation. | |
const robot_state::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. | |
const std::deque< double > & | getWayPointDurations () const |
robot_state::RobotStatePtr & | getWayPointPtr (std::size_t index) |
void | insertWayPoint (std::size_t index, const robot_state::RobotState &state, double dt) |
void | insertWayPoint (std::size_t index, const robot_state::RobotStatePtr &state, double dt) |
void | reverse () |
RobotTrajectory (const robot_model::RobotModelConstPtr &robot_model, const std::string &group) | |
RobotTrajectory (const robot_model::RobotModelConstPtr &robot_model, const robot_model::JointModelGroup *group) | |
void | setGroupName (const std::string &group_name) |
void | setRobotTrajectoryMsg (const robot_state::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. | |
void | setRobotTrajectoryMsg (const robot_state::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. | |
void | setRobotTrajectoryMsg (const robot_state::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. | |
void | setWayPointDurationFromPrevious (std::size_t index, double value) |
void | swap (robot_trajectory::RobotTrajectory &other) |
void | unwind () |
void | unwind (const robot_state::RobotState &state) |
Private Attributes | |
std::deque< double > | duration_from_previous_ |
const robot_model::JointModelGroup * | group_ |
robot_model::RobotModelConstPtr | robot_model_ |
std::deque < robot_state::RobotStatePtr > | waypoints_ |
Maintain a sequence of waypoints and the time durations between these waypoints.
Definition at line 52 of file robot_trajectory.h.
robot_trajectory::RobotTrajectory::RobotTrajectory | ( | const robot_model::RobotModelConstPtr & | robot_model, |
const std::string & | group | ||
) |
Definition at line 43 of file robot_trajectory.cpp.
robot_trajectory::RobotTrajectory::RobotTrajectory | ( | const robot_model::RobotModelConstPtr & | robot_model, |
const robot_model::JointModelGroup * | group | ||
) |
Definition at line 49 of file robot_trajectory.cpp.
void robot_trajectory::RobotTrajectory::addPrefixWayPoint | ( | const robot_state::RobotState & | state, |
double | dt | ||
) | [inline] |
Definition at line 161 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::addPrefixWayPoint | ( | const robot_state::RobotStatePtr & | state, |
double | dt | ||
) | [inline] |
Definition at line 166 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::addSuffixWayPoint | ( | const robot_state::RobotState & | state, |
double | dt | ||
) | [inline] |
Add a point to the trajectory.
state | - current robot state |
dt | - duration from previous |
Definition at line 144 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::addSuffixWayPoint | ( | const robot_state::RobotStatePtr & | state, |
double | dt | ||
) | [inline] |
Add a point to the trajectory.
state | - current robot state |
dt | - duration from previous |
Definition at line 154 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::append | ( | const RobotTrajectory & | source, |
double | dt | ||
) |
Add a trajectory to the end of the current trajectory.
source | - the trajectory to append to the end of current trajectory |
dt | - time step between last traj point in current traj, and first traj point of new traj |
Definition at line 85 of file robot_trajectory.cpp.
void robot_trajectory::RobotTrajectory::clear | ( | void | ) |
Definition at line 187 of file robot_trajectory.cpp.
bool robot_trajectory::RobotTrajectory::empty | ( | ) | const [inline] |
Definition at line 134 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.
The | duration from start. |
The | waypoint index before the supplied duration. |
The | waypoint index after (or equal to) the supplied duration. |
The | progress (0 to 1) between the two waypoints, based on time (not based on joint distances). |
Definition at line 371 of file robot_trajectory.cpp.
double robot_trajectory::RobotTrajectory::getAverageSegmentDuration | ( | ) | const |
Definition at line 68 of file robot_trajectory.cpp.
const robot_state::RobotState& robot_trajectory::RobotTrajectory::getFirstWayPoint | ( | ) | const [inline] |
Definition at line 88 of file robot_trajectory.h.
robot_state::RobotStatePtr& robot_trajectory::RobotTrajectory::getFirstWayPointPtr | ( | ) | [inline] |
Definition at line 103 of file robot_trajectory.h.
const robot_model::JointModelGroup* robot_trajectory::RobotTrajectory::getGroup | ( | ) | const [inline] |
Definition at line 64 of file robot_trajectory.h.
const std::string & robot_trajectory::RobotTrajectory::getGroupName | ( | ) | const |
Definition at line 60 of file robot_trajectory.cpp.
const robot_state::RobotState& robot_trajectory::RobotTrajectory::getLastWayPoint | ( | ) | const [inline] |
Definition at line 83 of file robot_trajectory.h.
robot_state::RobotStatePtr& robot_trajectory::RobotTrajectory::getLastWayPointPtr | ( | ) | [inline] |
Definition at line 98 of file robot_trajectory.h.
const robot_model::RobotModelConstPtr& robot_trajectory::RobotTrajectory::getRobotModel | ( | ) | const [inline] |
Definition at line 59 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::getRobotTrajectoryMsg | ( | moveit_msgs::RobotTrajectory & | trajectory | ) | const |
Definition at line 193 of file robot_trajectory.cpp.
bool robot_trajectory::RobotTrajectory::getStateAtDurationFromStart | ( | const double | request_duration, |
robot_state::RobotStatePtr & | output_state | ||
) | const |
Gets a robot state corresponding to a supplied duration from start for the trajectory, using linear time interpolation.
The | duration from start. |
The | resulting robot state. |
Definition at line 415 of file robot_trajectory.cpp.
const robot_state::RobotState& robot_trajectory::RobotTrajectory::getWayPoint | ( | std::size_t | index | ) | const [inline] |
Definition at line 78 of file robot_trajectory.h.
std::size_t robot_trajectory::RobotTrajectory::getWayPointCount | ( | ) | const [inline] |
Definition at line 73 of file robot_trajectory.h.
double robot_trajectory::RobotTrajectory::getWayPointDurationFromPrevious | ( | std::size_t | index | ) | const [inline] |
Definition at line 119 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.
The | waypoint index. |
Definition at line 402 of file robot_trajectory.cpp.
const std::deque<double>& robot_trajectory::RobotTrajectory::getWayPointDurations | ( | ) | const [inline] |
Definition at line 108 of file robot_trajectory.h.
robot_state::RobotStatePtr& robot_trajectory::RobotTrajectory::getWayPointPtr | ( | std::size_t | index | ) | [inline] |
Definition at line 93 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::insertWayPoint | ( | std::size_t | index, |
const robot_state::RobotState & | state, | ||
double | dt | ||
) | [inline] |
Definition at line 173 of file robot_trajectory.h.
void robot_trajectory::RobotTrajectory::insertWayPoint | ( | std::size_t | index, |
const robot_state::RobotStatePtr & | state, | ||
double | dt | ||
) | [inline] |
Definition at line 178 of file robot_trajectory.h.
Definition at line 95 of file robot_trajectory.cpp.
void robot_trajectory::RobotTrajectory::setGroupName | ( | const std::string & | group_name | ) |
Definition at line 55 of file robot_trajectory.cpp.
void robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg | ( | const robot_state::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 287 of file robot_trajectory.cpp.
void robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg | ( | const robot_state::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 313 of file robot_trajectory.cpp.
void robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg | ( | const robot_state::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 362 of file robot_trajectory.cpp.
void robot_trajectory::RobotTrajectory::setWayPointDurationFromPrevious | ( | std::size_t | index, |
double | value | ||
) | [inline] |
Definition at line 127 of file robot_trajectory.h.
Definition at line 77 of file robot_trajectory.cpp.
Definition at line 106 of file robot_trajectory.cpp.
void robot_trajectory::RobotTrajectory::unwind | ( | const robot_state::RobotState & | state | ) |
Definition at line 141 of file robot_trajectory.cpp.
std::deque<double> robot_trajectory::RobotTrajectory::duration_from_previous_ [private] |
Definition at line 254 of file robot_trajectory.h.
const robot_model::JointModelGroup* robot_trajectory::RobotTrajectory::group_ [private] |
Definition at line 252 of file robot_trajectory.h.
robot_model::RobotModelConstPtr robot_trajectory::RobotTrajectory::robot_model_ [private] |
Definition at line 251 of file robot_trajectory.h.
std::deque<robot_state::RobotStatePtr> robot_trajectory::RobotTrajectory::waypoints_ [private] |
Definition at line 253 of file robot_trajectory.h.