37 #ifndef CHOMP_TRAJECTORY_H_
38 #define CHOMP_TRAJECTORY_H_
43 #include "API/Device/robot.hpp"
44 #include "API/Trajectory/trajectory.hpp"
46 #include "chompUtils.hpp"
47 #include "chompPlanningGroup.hpp"
89 double& operator() (
int traj_point,
int joint);
91 double operator() (
int traj_point,
int joint)
const;
93 Eigen::MatrixXd::RowXpr getTrajectoryPoint(
int traj_point);
96 void getTrajectoryPointP3d(
int traj_point, Eigen::VectorXd& jnt_array)
const;
98 Eigen::MatrixXd::ColXpr getJointTrajectory(
int joint);
175 template <
typename Derived>
178 double getDuration()
const;
181 Robot* getRobot() {
return robot_model_; }
195 double discretization_;
197 Eigen::MatrixXd trajectory_;
200 std::vector<int> full_trajectory_index_;
205 inline double& ChompTrajectory::operator() (
int traj_point,
int joint)
207 return trajectory_(traj_point, joint);
210 inline double ChompTrajectory::operator() (
int traj_point,
int joint)
const
212 return trajectory_(traj_point, joint);
215 inline Eigen::MatrixXd::RowXpr ChompTrajectory::getTrajectoryPoint(
int traj_point)
217 return trajectory_.row(traj_point);
220 inline Eigen::MatrixXd::ColXpr ChompTrajectory::getJointTrajectory(
int joint)
222 return trajectory_.col(joint);
232 return (end_index_ - start_index_)+1;
242 return discretization_;
247 start_index_ = start_index;
248 end_index_ = end_index;
287 return full_trajectory_index_[i];
290 template <
typename Derived>
293 velocities.setZero();
294 double invTime = 1.0 / discretization_;
296 for (
int k=-DIFF_RULE_LENGTH/2; k<=DIFF_RULE_LENGTH/2; k++)
298 velocities += (invTime * DIFF_RULES[0][k+DIFF_RULE_LENGTH/2]) * trajectory_.row(traj_point+k).transpose();
302 inline double ChompTrajectory::getDuration()
const {
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
Definition: chompTrajectory.cpp:185
int getFullTrajectoryIndex(int i) const
Gets the index in the full trajectory which was copied to this group trajectory.
Definition: chompTrajectory.hpp:285
Contains information about a planning group.
Definition: chompPlanningGroup.hpp:38
int getStartIndex() const
Gets the start index.
Definition: chompTrajectory.hpp:251
void getJointVelocities(int traj_point, Eigen::MatrixBase< Derived > &velocities)
Gets the joint velocities at the given trajectory point.
Definition: chompTrajectory.hpp:291
int getEndIndex() const
Gets the end index.
Definition: chompTrajectory.hpp:256
Represents a discretized joint-space trajectory for CHOMP.
Definition: chompTrajectory.hpp:60
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.
Definition: chompTrajectory.hpp:266
virtual ~ChompTrajectory()
Destructor.
Definition: chompTrajectory.cpp:154
This class holds a the robot represented by a kinematic chain.
Definition: robot.hpp:42
int getNumPoints() const
Gets the number of points in the trajectory.
Definition: chompTrajectory.hpp:225
double getDiscretization() const
Gets the discretization time interval of the trajectory.
Definition: chompTrajectory.hpp:240
void setStartEndIndex(int start_index, int end_index)
Sets the start and end index for the modifiable part of the trajectory.
Definition: chompTrajectory.hpp:245
int getNumJoints() const
Gets the number of joints in each trajectory point.
Definition: chompTrajectory.hpp:235
Definition: trajectory.hpp:40
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
Definition: chompTrajectory.cpp:165
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
Definition: chompTrajectory.hpp:261
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeJointTrajectoryBlock(int joint)
Gets the block of free (optimizable) trajectory for a single joint.
Definition: chompTrajectory.hpp:274
int getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
Definition: chompTrajectory.hpp:230