37 #ifndef CHOMP_TRAJECTORY_H_ 38 #define CHOMP_TRAJECTORY_H_ 40 #include <trajectory_msgs/JointTrajectory.h> 44 #include <moveit_msgs/MotionPlanDetailedResponse.h> 45 #include <moveit_msgs/MotionPlanRequest.h> 48 #include <eigen3/Eigen/Core> 61 ChompTrajectory(
const moveit::core::RobotModelConstPtr& robot_model,
double duration,
double discretization,
62 std::string groupName);
67 ChompTrajectory(
const moveit::core::RobotModelConstPtr& robot_model,
int num_points,
double discretization,
68 std::string groupName);
76 ChompTrajectory(
const moveit::core::RobotModelConstPtr& robot_model,
const std::string& planning_group,
77 const trajectory_msgs::JointTrajectory& traj);
86 double operator()(
int traj_point,
int joint)
const;
151 int num_joints_trajectory,
int trajectory_msgs_point,
152 int chomp_trajectory_point);
200 template <
typename Derived>
290 inline Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic>
301 template <
typename Derived>
304 velocities.setZero();
double & operator()(int traj_point, int joint)
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
ChompTrajectory(const moveit::core::RobotModelConstPtr &robot_model, double duration, double discretization, std::string groupName)
Constructs a trajectory for a given robot model, trajectory duration, and discretization.
bool fillInFromTrajectory(moveit_msgs::MotionPlanDetailedResponse &res)
Receives the path obtained from a given MotionPlanDetailedResponse res object's trajectory (e...
virtual ~ChompTrajectory()
Destructor.
void fillInCubicInterpolation()
Generates a cubic interpolation of the trajectory from the start index to end index.
void getJointVelocities(int traj_point, Eigen::MatrixBase< Derived > &velocities)
Gets the joint velocities at the given trajectory point.
std::vector< int > full_trajectory_index_
static const int DIFF_RULE_LENGTH
int getStartIndex() const
Gets the start index.
void assignCHOMPTrajectoryPointFromInputTrajectoryPoint(moveit_msgs::RobotTrajectory trajectory_msg, int num_joints_trajectory, int trajectory_msgs_point, int chomp_trajectory_point)
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeJointTrajectoryBlock(int joint)
Gets the block of free (optimizable) trajectory for a single joint.
int getNumPoints() const
Gets the number of points in the trajectory.
Eigen::MatrixXd trajectory_
void init()
Allocates memory for the trajectory.
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)
int getEndIndex() const
Gets the end index.
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
std::string planning_group_name_
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
static const double DIFF_RULES[3][DIFF_RULE_LENGTH]
Represents a discretized joint-space trajectory for CHOMP.
double getDuration() const
void overwriteTrajectory(const trajectory_msgs::JointTrajectory &traj)
int getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
void fillInLinearInterpolation()
Generates a linearly interpolated trajectory from the start index to end index.
double getDiscretization() const
Gets the discretization time interval of the trajectory.
void setStartEndIndex(int start_index, int end_index)
Sets the start and end index for the modifiable part of the trajectory.
int getNumJoints() const
Gets the number of joints in each trajectory point.
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.