Public Member Functions | Private Member Functions | Private Attributes
chomp::ChompTrajectory Class Reference

Represents a discretized joint-space trajectory for CHOMP. More...

#include <chomp_trajectory.h>

List of all members.

Public Member Functions

 ChompTrajectory (const planning_models::KinematicModel *robot_model, double duration, double discretization, std::string groupName)
 Constructs a trajectory for a given robot model, trajectory duration, and discretization.
 ChompTrajectory (const planning_models::KinematicModel *robot_model, int num_points, double discretization, std::string groupName)
 Constructs a trajectory for a given robot model, number of trajectory points, and discretization.
 ChompTrajectory (const ChompTrajectory &source_traj, const std::string &planning_group, int diff_rule_length)
 Creates a new containing only the joints of interest, and adds padding to the start and end if needed, to have enough trajectory points for the differentiation rules.
 ChompTrajectory (const planning_models::KinematicModel *robot_model, const std::string &planning_group, const trajectory_msgs::JointTrajectory &traj)
void fillInMinJerk ()
 Generates a minimum jerk trajectory from the start index to end index.
double getDiscretization () const
 Gets the discretization time interval of the trajectory.
double getDuration () const
int getEndIndex () const
 Gets the end index.
Eigen::Block< Eigen::MatrixXd,
Eigen::Dynamic, Eigen::Dynamic > 
getFreeJointTrajectoryBlock (int joint)
 Gets the block of free (optimizable) trajectory for a single joint.
Eigen::Block< Eigen::MatrixXd,
Eigen::Dynamic, Eigen::Dynamic > 
getFreeTrajectoryBlock ()
 Gets the block of the trajectory which can be optimized.
int getFullTrajectoryIndex (int i) const
 Gets the index in the full trajectory which was copied to this group trajectory.
Eigen::MatrixXd::ColXpr getJointTrajectory (int joint)
template<typename Derived >
void getJointVelocities (int traj_point, Eigen::MatrixBase< Derived > &velocities)
 Gets the joint velocities at the given trajectory point.
int getNumFreePoints () const
 Gets the number of points (that are free to be optimized) in the trajectory.
int getNumJoints () const
 Gets the number of joints in each trajectory point.
int getNumPoints () const
 Gets the number of points in the trajectory.
int getStartIndex () const
 Gets the start index.
Eigen::MatrixXd & getTrajectory ()
 Gets the entire trajectory matrix.
Eigen::MatrixXd::RowXpr getTrajectoryPoint (int traj_point)
double & operator() (int traj_point, int joint)
double operator() (int traj_point, int joint) const
void overwriteTrajectory (const trajectory_msgs::JointTrajectory &traj)
void setStartEndIndex (int start_index, int end_index)
 Sets the start and end index for the modifiable part of the trajectory.
void updateFromGroupTrajectory (const ChompTrajectory &group_trajectory)
 Updates the full trajectory (*this) from the group trajectory.
virtual ~ChompTrajectory ()
 Destructor.

Private Member Functions

void init ()
 Allocates memory for the trajectory.

Private Attributes

double discretization_
double duration_
int end_index_
std::vector< int > full_trajectory_index_
int num_joints_
int num_points_
std::string planning_group_name_
int start_index_
Eigen::MatrixXd trajectory_

Detailed Description

Represents a discretized joint-space trajectory for CHOMP.

Definition at line 53 of file chomp_trajectory.h.


Constructor & Destructor Documentation

chomp::ChompTrajectory::ChompTrajectory ( const planning_models::KinematicModel robot_model,
double  duration,
double  discretization,
std::string  groupName 
)

Constructs a trajectory for a given robot model, trajectory duration, and discretization.

Definition at line 45 of file chomp_trajectory.cpp.

chomp::ChompTrajectory::ChompTrajectory ( const planning_models::KinematicModel robot_model,
int  num_points,
double  discretization,
std::string  groupName 
)

Constructs a trajectory for a given robot model, number of trajectory points, and discretization.

Definition at line 59 of file chomp_trajectory.cpp.

chomp::ChompTrajectory::ChompTrajectory ( const ChompTrajectory source_traj,
const std::string &  planning_group,
int  diff_rule_length 
)

Creates a new containing only the joints of interest, and adds padding to the start and end if needed, to have enough trajectory points for the differentiation rules.

Definition at line 73 of file chomp_trajectory.cpp.

chomp::ChompTrajectory::ChompTrajectory ( const planning_models::KinematicModel robot_model,
const std::string &  planning_group,
const trajectory_msgs::JointTrajectory &  traj 
)

Definition at line 110 of file chomp_trajectory.cpp.

Destructor.

Definition at line 143 of file chomp_trajectory.cpp.


Member Function Documentation

Generates a minimum jerk trajectory from the start index to end index.

Only modifies points from start_index_ to end_index_, inclusive.

Definition at line 170 of file chomp_trajectory.cpp.

double chomp::ChompTrajectory::getDiscretization ( ) const [inline]

Gets the discretization time interval of the trajectory.

Definition at line 222 of file chomp_trajectory.h.

double chomp::ChompTrajectory::getDuration ( ) const [inline]

Definition at line 275 of file chomp_trajectory.h.

int chomp::ChompTrajectory::getEndIndex ( ) const [inline]

Gets the end index.

Definition at line 238 of file chomp_trajectory.h.

Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > chomp::ChompTrajectory::getFreeJointTrajectoryBlock ( int  joint) [inline]

Gets the block of free (optimizable) trajectory for a single joint.

Definition at line 253 of file chomp_trajectory.h.

Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > chomp::ChompTrajectory::getFreeTrajectoryBlock ( ) [inline]

Gets the block of the trajectory which can be optimized.

Definition at line 248 of file chomp_trajectory.h.

int chomp::ChompTrajectory::getFullTrajectoryIndex ( int  i) const [inline]

Gets the index in the full trajectory which was copied to this group trajectory.

Definition at line 258 of file chomp_trajectory.h.

Eigen::MatrixXd::ColXpr chomp::ChompTrajectory::getJointTrajectory ( int  joint) [inline]

Definition at line 202 of file chomp_trajectory.h.

template<typename Derived >
void chomp::ChompTrajectory::getJointVelocities ( int  traj_point,
Eigen::MatrixBase< Derived > &  velocities 
)

Gets the joint velocities at the given trajectory point.

Definition at line 264 of file chomp_trajectory.h.

Gets the number of points (that are free to be optimized) in the trajectory.

Definition at line 212 of file chomp_trajectory.h.

int chomp::ChompTrajectory::getNumJoints ( ) const [inline]

Gets the number of joints in each trajectory point.

Definition at line 217 of file chomp_trajectory.h.

int chomp::ChompTrajectory::getNumPoints ( ) const [inline]

Gets the number of points in the trajectory.

Definition at line 207 of file chomp_trajectory.h.

int chomp::ChompTrajectory::getStartIndex ( ) const [inline]

Gets the start index.

Definition at line 233 of file chomp_trajectory.h.

Eigen::MatrixXd & chomp::ChompTrajectory::getTrajectory ( ) [inline]

Gets the entire trajectory matrix.

Definition at line 243 of file chomp_trajectory.h.

Eigen::MatrixXd::RowXpr chomp::ChompTrajectory::getTrajectoryPoint ( int  traj_point) [inline]

Definition at line 197 of file chomp_trajectory.h.

void chomp::ChompTrajectory::init ( ) [private]

Allocates memory for the trajectory.

Definition at line 155 of file chomp_trajectory.cpp.

double & chomp::ChompTrajectory::operator() ( int  traj_point,
int  joint 
) [inline]

Definition at line 187 of file chomp_trajectory.h.

double chomp::ChompTrajectory::operator() ( int  traj_point,
int  joint 
) const [inline]

Definition at line 192 of file chomp_trajectory.h.

void chomp::ChompTrajectory::overwriteTrajectory ( const trajectory_msgs::JointTrajectory &  traj)

Definition at line 147 of file chomp_trajectory.cpp.

void chomp::ChompTrajectory::setStartEndIndex ( int  start_index,
int  end_index 
) [inline]

Sets the start and end index for the modifiable part of the trajectory.

(Everything before the start and after the end index is considered fixed) The values default to 1 and getNumPoints()-2

Definition at line 227 of file chomp_trajectory.h.

Updates the full trajectory (*this) from the group trajectory.

Definition at line 161 of file chomp_trajectory.cpp.


Member Data Documentation

Discretization of the trajectory

Definition at line 177 of file chomp_trajectory.h.

Duration of the trajectory

Definition at line 178 of file chomp_trajectory.h.

End index (inclusive) of trajectory to be optimized (everything after it will not be modified)

Definition at line 181 of file chomp_trajectory.h.

If this is a "group" trajectory, the index from the original traj which each element here was copied

Definition at line 182 of file chomp_trajectory.h.

Number of joints in each trajectory point

Definition at line 176 of file chomp_trajectory.h.

Number of points in the trajectory

Definition at line 175 of file chomp_trajectory.h.

Planning group that this trajectory corresponds to, if any

Definition at line 174 of file chomp_trajectory.h.

Start index (inclusive) of trajectory to be optimized (everything before it will not be modified)

Definition at line 180 of file chomp_trajectory.h.

Eigen::MatrixXd chomp::ChompTrajectory::trajectory_ [private]

Storage for the actual trajectory

Definition at line 179 of file chomp_trajectory.h.


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


chomp_motion_planner
Author(s): Mrinal Kalakrishnan / mail@mrinal.net
autogenerated on Thu Dec 12 2013 11:08:58