Public Member Functions | Private Attributes
robot_trajectory::RobotTrajectory Class Reference

Maintain a sequence of waypoints and the time durations between these waypoints. More...

#include <robot_trajectory.h>

List of all members.

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)
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::RobotStategetFirstWayPoint () const
robot_state::RobotStatePtr & getFirstWayPointPtr ()
const
robot_model::JointModelGroup
getGroup () const
const std::string & getGroupName () const
const robot_state::RobotStategetLastWayPoint () 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::RobotStategetWayPoint (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 &kmodel, const std::string &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_

Detailed Description

Maintain a sequence of waypoints and the time durations between these waypoints.

Definition at line 50 of file robot_trajectory.h.


Constructor & Destructor Documentation

robot_trajectory::RobotTrajectory::RobotTrajectory ( const robot_model::RobotModelConstPtr &  kmodel,
const std::string &  group 
)

Definition at line 43 of file robot_trajectory.cpp.


Member Function Documentation

void robot_trajectory::RobotTrajectory::addPrefixWayPoint ( const robot_state::RobotState state,
double  dt 
) [inline]

Definition at line 157 of file robot_trajectory.h.

void robot_trajectory::RobotTrajectory::addPrefixWayPoint ( const robot_state::RobotStatePtr &  state,
double  dt 
) [inline]

Definition at line 162 of file robot_trajectory.h.

void robot_trajectory::RobotTrajectory::addSuffixWayPoint ( const robot_state::RobotState state,
double  dt 
) [inline]

Add a point to the trajectory.

Parameters:
state- current robot state
dt- duration from previous

Definition at line 140 of file robot_trajectory.h.

void robot_trajectory::RobotTrajectory::addSuffixWayPoint ( const robot_state::RobotStatePtr &  state,
double  dt 
) [inline]

Add a point to the trajectory.

Parameters:
state- current robot state
dt- duration from previous

Definition at line 150 of file robot_trajectory.h.

void robot_trajectory::RobotTrajectory::append ( const RobotTrajectory source,
double  dt 
)

Definition at line 78 of file robot_trajectory.cpp.

Definition at line 178 of file robot_trajectory.cpp.

Definition at line 130 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.

Parameters:
Theduration from start.
Thewaypoint index before the supplied duration.
Thewaypoint index after (or equal to) the supplied duration.
Theprogress (0 to 1) between the two waypoints, based on time (not based on joint distances).

Definition at line 350 of file robot_trajectory.cpp.

Definition at line 62 of file robot_trajectory.cpp.

Definition at line 84 of file robot_trajectory.h.

robot_state::RobotStatePtr& robot_trajectory::RobotTrajectory::getFirstWayPointPtr ( ) [inline]

Definition at line 99 of file robot_trajectory.h.

Definition at line 60 of file robot_trajectory.h.

const std::string & robot_trajectory::RobotTrajectory::getGroupName ( ) const

Definition at line 54 of file robot_trajectory.cpp.

Definition at line 79 of file robot_trajectory.h.

robot_state::RobotStatePtr& robot_trajectory::RobotTrajectory::getLastWayPointPtr ( ) [inline]

Definition at line 94 of file robot_trajectory.h.

const robot_model::RobotModelConstPtr& robot_trajectory::RobotTrajectory::getRobotModel ( ) const [inline]

Definition at line 55 of file robot_trajectory.h.

void robot_trajectory::RobotTrajectory::getRobotTrajectoryMsg ( moveit_msgs::RobotTrajectory &  trajectory) const

Definition at line 184 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.

Parameters:
Theduration from start.
Theresulting robot state.
Returns:
True if state is valid, false otherwise (trajectory is empty).

Definition at line 393 of file robot_trajectory.cpp.

const robot_state::RobotState& robot_trajectory::RobotTrajectory::getWayPoint ( std::size_t  index) const [inline]

Definition at line 74 of file robot_trajectory.h.

Definition at line 69 of file robot_trajectory.h.

double robot_trajectory::RobotTrajectory::getWayPointDurationFromPrevious ( std::size_t  index) const [inline]

Definition at line 115 of file robot_trajectory.h.

Returns the duration after start that a waypoint will be reached.

Parameters:
Thewaypoint index.
Returns:
The duration from start; retuns -1.0 if index is out of range.

Definition at line 380 of file robot_trajectory.cpp.

const std::deque<double>& robot_trajectory::RobotTrajectory::getWayPointDurations ( ) const [inline]

Definition at line 104 of file robot_trajectory.h.

robot_state::RobotStatePtr& robot_trajectory::RobotTrajectory::getWayPointPtr ( std::size_t  index) [inline]

Definition at line 89 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 169 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 174 of file robot_trajectory.h.

Definition at line 87 of file robot_trajectory.cpp.

void robot_trajectory::RobotTrajectory::setGroupName ( const std::string &  group_name)

Definition at line 49 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 273 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 299 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 342 of file robot_trajectory.cpp.

void robot_trajectory::RobotTrajectory::setWayPointDurationFromPrevious ( std::size_t  index,
double  value 
) [inline]

Definition at line 123 of file robot_trajectory.h.

Definition at line 70 of file robot_trajectory.cpp.

Definition at line 98 of file robot_trajectory.cpp.

Definition at line 133 of file robot_trajectory.cpp.


Member Data Documentation

Definition at line 237 of file robot_trajectory.h.

Definition at line 235 of file robot_trajectory.h.

robot_model::RobotModelConstPtr robot_trajectory::RobotTrajectory::robot_model_ [private]

Definition at line 234 of file robot_trajectory.h.

std::deque<robot_state::RobotStatePtr> robot_trajectory::RobotTrajectory::waypoints_ [private]

Definition at line 236 of file robot_trajectory.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:54