Go to the documentation of this file.
39 #include <trajectory_msgs/JointTrajectory.h>
43 #include <moveit_msgs/MotionPlanDetailedResponse.h>
44 #include <moveit_msgs/MotionPlanRequest.h>
47 #include <eigen3/Eigen/Core>
61 const std::string& group_name);
66 ChompTrajectory(
const moveit::core::RobotModelConstPtr& robot_model,
size_t num_points,
double discretization,
67 const std::string& group_name);
75 ChompTrajectory(
const moveit::core::RobotModelConstPtr& robot_model,
const std::string& group_name,
76 const trajectory_msgs::JointTrajectory& traj);
83 double&
operator()(
size_t traj_point,
size_t joint);
85 double operator()(
size_t traj_point,
size_t joint)
const;
195 template <
typename Derived>
282 inline Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic>
293 template <
typename Derived>
296 velocities.setZero();
Represents a discretized joint-space trajectory for CHOMP.
void fillInCubicInterpolation()
Generates a cubic interpolation of the trajectory from the start index to end index.
static const double DIFF_RULES[3][DIFF_RULE_LENGTH]
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
std::chrono::system_clock::duration duration
bool fillInFromTrajectory(const robot_trajectory::RobotTrajectory &trajectory)
Receives the path obtained from a given MotionPlanDetailedResponse res object's trajectory (e....
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
double getDuration() const
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
double getDiscretization() const
Gets the discretization time interval of the trajectory.
ChompTrajectory(const moveit::core::RobotModelConstPtr &robot_model, double duration, double discretization, const std::string &group_name)
Constructs a trajectory for a given robot model, trajectory duration, and discretization.
std::vector< size_t > full_trajectory_index_
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.
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.
virtual ~ChompTrajectory()=default
Destructor.
size_t getStartIndex() const
Gets the start index.
Eigen::MatrixXd::ColXpr getJointTrajectory(int joint)
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
std::string planning_group_name_
void init()
Allocates memory for the trajectory.
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.
size_t getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
size_t getFullTrajectoryIndex(size_t i) const
Gets the index in the full trajectory which was copied to this group trajectory.
size_t getEndIndex() const
Gets the end index.
static const int DIFF_RULE_LENGTH
size_t getNumPoints() const
Gets the number of points in the trajectory.
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
void fillInLinearInterpolation()
Generates a linearly interpolated trajectory from the start index to end index.
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.
Eigen::MatrixXd trajectory_
chomp_motion_planner
Author(s): Gil Jones
, Mrinal Kalakrishnan
autogenerated on Sat May 3 2025 02:26:05