Represents a discretized joint-space trajectory for CHOMP. More...
#include <chomp_trajectory.h>
Public Member Functions | |
ChompTrajectory (const ChompRobotModel *robot_model, const ChompRobotModel::ChompPlanningGroup *planning_group, const trajectory_msgs::JointTrajectory &traj) | |
ChompTrajectory (const ChompTrajectory &source_traj, const ChompRobotModel::ChompPlanningGroup *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 ChompRobotModel *robot_model, int num_points, double discretization) | |
Constructs a trajectory for a given robot model, number of trajectory points, and discretization. | |
ChompTrajectory (const ChompRobotModel *robot_model, double duration, double discretization) | |
Constructs a trajectory for a given robot model, trajectory duration, and discretization. | |
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) |
void | getTrajectoryPointKDL (int traj_point, KDL::JntArray &kdl_jnt_array) const |
double | operator() (int traj_point, int joint) const |
double & | operator() (int traj_point, int joint) |
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_ |
const ChompRobotModel::ChompPlanningGroup * | planning_group_ |
const ChompRobotModel * | robot_model_ |
int | start_index_ |
Eigen::MatrixXd | trajectory_ |
Represents a discretized joint-space trajectory for CHOMP.
Definition at line 55 of file chomp_trajectory.h.
chomp::ChompTrajectory::ChompTrajectory | ( | const ChompRobotModel * | robot_model, | |
double | duration, | |||
double | discretization | |||
) |
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 ChompRobotModel * | robot_model, | |
int | num_points, | |||
double | discretization | |||
) |
Constructs a trajectory for a given robot model, number of trajectory points, and discretization.
Definition at line 58 of file chomp_trajectory.cpp.
chomp::ChompTrajectory::ChompTrajectory | ( | const ChompTrajectory & | source_traj, | |
const ChompRobotModel::ChompPlanningGroup * | 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 71 of file chomp_trajectory.cpp.
chomp::ChompTrajectory::ChompTrajectory | ( | const ChompRobotModel * | robot_model, | |
const ChompRobotModel::ChompPlanningGroup * | planning_group, | |||
const trajectory_msgs::JointTrajectory & | traj | |||
) |
Definition at line 110 of file chomp_trajectory.cpp.
chomp::ChompTrajectory::~ChompTrajectory | ( | ) | [virtual] |
Destructor.
Definition at line 142 of file chomp_trajectory.cpp.
void chomp::ChompTrajectory::fillInMinJerk | ( | ) |
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 180 of file chomp_trajectory.cpp.
double chomp::ChompTrajectory::getDiscretization | ( | ) | const [inline] |
Gets the discretization time interval of the trajectory.
Definition at line 226 of file chomp_trajectory.h.
double chomp::ChompTrajectory::getDuration | ( | ) | const [inline] |
Definition at line 285 of file chomp_trajectory.h.
int chomp::ChompTrajectory::getEndIndex | ( | ) | const [inline] |
Gets the end index.
Definition at line 242 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 257 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 252 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 268 of file chomp_trajectory.h.
Eigen::MatrixXd::ColXpr chomp::ChompTrajectory::getJointTrajectory | ( | int | joint | ) | [inline] |
Definition at line 206 of file chomp_trajectory.h.
void chomp::ChompTrajectory::getJointVelocities | ( | int | traj_point, | |
Eigen::MatrixBase< Derived > & | velocities | |||
) | [inline] |
Gets the joint velocities at the given trajectory point.
Definition at line 274 of file chomp_trajectory.h.
int chomp::ChompTrajectory::getNumFreePoints | ( | ) | const [inline] |
Gets the number of points (that are free to be optimized) in the trajectory.
Definition at line 216 of file chomp_trajectory.h.
int chomp::ChompTrajectory::getNumJoints | ( | ) | const [inline] |
Gets the number of joints in each trajectory point.
Definition at line 221 of file chomp_trajectory.h.
int chomp::ChompTrajectory::getNumPoints | ( | ) | const [inline] |
Gets the number of points in the trajectory.
Definition at line 211 of file chomp_trajectory.h.
int chomp::ChompTrajectory::getStartIndex | ( | ) | const [inline] |
Gets the start index.
Definition at line 237 of file chomp_trajectory.h.
Eigen::MatrixXd & chomp::ChompTrajectory::getTrajectory | ( | ) | [inline] |
Gets the entire trajectory matrix.
Definition at line 247 of file chomp_trajectory.h.
Eigen::MatrixXd::RowXpr chomp::ChompTrajectory::getTrajectoryPoint | ( | int | traj_point | ) | [inline] |
Definition at line 201 of file chomp_trajectory.h.
void chomp::ChompTrajectory::getTrajectoryPointKDL | ( | int | traj_point, | |
KDL::JntArray & | kdl_jnt_array | |||
) | const [inline] |
Definition at line 262 of file chomp_trajectory.h.
void chomp::ChompTrajectory::init | ( | ) | [private] |
Allocates memory for the trajectory.
Definition at line 163 of file chomp_trajectory.cpp.
double chomp::ChompTrajectory::operator() | ( | int | traj_point, | |
int | joint | |||
) | const [inline] |
Definition at line 196 of file chomp_trajectory.h.
double & chomp::ChompTrajectory::operator() | ( | int | traj_point, | |
int | joint | |||
) | [inline] |
Definition at line 191 of file chomp_trajectory.h.
void chomp::ChompTrajectory::overwriteTrajectory | ( | const trajectory_msgs::JointTrajectory & | traj | ) |
Definition at line 146 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 231 of file chomp_trajectory.h.
void chomp::ChompTrajectory::updateFromGroupTrajectory | ( | const ChompTrajectory & | group_trajectory | ) |
Updates the full trajectory (*this) from the group trajectory.
Definition at line 169 of file chomp_trajectory.cpp.
double chomp::ChompTrajectory::discretization_ [private] |
Discretization of the trajectory
Definition at line 181 of file chomp_trajectory.h.
double chomp::ChompTrajectory::duration_ [private] |
Duration of the trajectory
Definition at line 182 of file chomp_trajectory.h.
int chomp::ChompTrajectory::end_index_ [private] |
End index (inclusive) of trajectory to be optimized (everything after it will not be modified)
Definition at line 185 of file chomp_trajectory.h.
std::vector<int> chomp::ChompTrajectory::full_trajectory_index_ [private] |
If this is a "group" trajectory, the index from the original traj which each element here was copied
Definition at line 186 of file chomp_trajectory.h.
int chomp::ChompTrajectory::num_joints_ [private] |
Number of joints in each trajectory point
Definition at line 180 of file chomp_trajectory.h.
int chomp::ChompTrajectory::num_points_ [private] |
Number of points in the trajectory
Definition at line 179 of file chomp_trajectory.h.
Planning group that this trajectory corresponds to, if any
Definition at line 178 of file chomp_trajectory.h.
const ChompRobotModel* chomp::ChompTrajectory::robot_model_ [private] |
Robot Model
Definition at line 177 of file chomp_trajectory.h.
int chomp::ChompTrajectory::start_index_ [private] |
Start index (inclusive) of trajectory to be optimized (everything before it will not be modified)
Definition at line 184 of file chomp_trajectory.h.
Eigen::MatrixXd chomp::ChompTrajectory::trajectory_ [private] |
Storage for the actual trajectory
Definition at line 183 of file chomp_trajectory.h.