42#include <eigen3/Eigen/Core> 
   43#include <moveit_msgs/msg/motion_plan_detailed_response.hpp> 
   44#include <moveit_msgs/msg/motion_plan_request.hpp> 
   45#include <trajectory_msgs/msg/joint_trajectory.hpp> 
   59  ChompTrajectory(
const moveit::core::RobotModelConstPtr& robot_model, 
double duration, 
double discretization,
 
   60                  const std::string& group_name);
 
   65  ChompTrajectory(
const moveit::core::RobotModelConstPtr& robot_model, 
size_t num_points, 
double discretization,
 
   66                  const std::string& group_name);
 
   74  ChompTrajectory(
const moveit::core::RobotModelConstPtr& robot_model, 
const std::string& group_name,
 
   75                  const trajectory_msgs::msg::JointTrajectory& traj);
 
   82  double& 
operator()(
size_t traj_point, 
size_t joint);
 
   84  double operator()(
size_t traj_point, 
size_t joint) 
const;
 
  194  template <
typename Derived>
 
  202  std::string planning_group_name_;  
 
  205  double discretization_;            
 
  207  Eigen::MatrixXd trajectory_;       
 
  210  std::vector<size_t> full_trajectory_index_;  
 
 
  217  return trajectory_(traj_point, joint);
 
 
  222  return trajectory_(traj_point, joint);
 
 
  227  return trajectory_.row(traj_point);
 
 
  232  return trajectory_.col(joint);
 
 
  242  return (end_index_ - start_index_) + 1;
 
 
  252  return discretization_;
 
 
  257  start_index_ = start_index;
 
  258  end_index_ = end_index;
 
 
  281inline Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic>
 
  289  return full_trajectory_index_[i];
 
 
  292template <
typename Derived>
 
  295  velocities.setZero();
 
  296  double inv_time = 1.0 / discretization_;
 
  298  for (
int k = -DIFF_RULE_LENGTH / 2; k <= DIFF_RULE_LENGTH / 2; ++k)
 
  300    velocities += (inv_time * DIFF_RULES[0][k + DIFF_RULE_LENGTH / 2]) * trajectory_.row(traj_point + k).transpose();
 
 
Represents a discretized joint-space trajectory for CHOMP.
 
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.
 
double getDuration() const
 
ChompTrajectory(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const trajectory_msgs::msg::JointTrajectory &traj)
 
void assignCHOMPTrajectoryPointFromRobotState(const moveit::core::RobotState &source, size_t chomp_trajectory_point, const moveit::core::JointModelGroup *group)
This function assigns the given source RobotState to the row at index chomp_trajectory_point.
 
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
 
size_t getEndIndex() const
Gets the end index.
 
size_t getStartIndex() const
Gets the start index.
 
double getDiscretization() const
Gets the discretization time interval of the trajectory.
 
size_t getNumPoints() const
Gets the number of points in the trajectory.
 
void fillInCubicInterpolation()
Generates a cubic interpolation of the trajectory from the start index to end index.
 
bool fillInFromTrajectory(const robot_trajectory::RobotTrajectory &trajectory)
Receives the path obtained from a given MotionPlanDetailedResponse res object's trajectory (e....
 
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeJointTrajectoryBlock(size_t joint)
Gets the block of free (optimizable) trajectory for a single joint.
 
void getJointVelocities(size_t traj_point, Eigen::MatrixBase< Derived > &velocities)
Gets the joint velocities at the given trajectory point.
 
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
 
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
 
virtual ~ChompTrajectory()=default
Destructor.
 
size_t getFullTrajectoryIndex(size_t i) const
Gets the index in the full trajectory which was copied to this group trajectory.
 
Eigen::MatrixXd::ColXpr getJointTrajectory(int joint)
 
void fillInLinearInterpolation()
Generates a linearly interpolated trajectory from the start index to end index.
 
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
 
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
 
size_t getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
 
double & operator()(size_t traj_point, size_t joint)
 
void setStartEndIndex(size_t start_index, size_t end_index)
Sets the start and end index for the modifiable part of the trajectory.
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
Maintain a sequence of waypoints and the time durations between these waypoints.