moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Represents a discretized joint-space trajectory for CHOMP. More...
#include <chomp_trajectory.h>
Public Member Functions | |
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. | |
ChompTrajectory (const moveit::core::RobotModelConstPtr &robot_model, size_t num_points, double discretization, const std::string &group_name) | |
Constructs a trajectory for a given robot model, number of trajectory points, and discretization. | |
ChompTrajectory (const ChompTrajectory &source_traj, const std::string &group_name, 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 moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const trajectory_msgs::msg::JointTrajectory &traj) | |
virtual | ~ChompTrajectory ()=default |
Destructor. | |
double & | operator() (size_t traj_point, size_t joint) |
double | operator() (size_t traj_point, size_t joint) const |
Eigen::MatrixXd::RowXpr | getTrajectoryPoint (int traj_point) |
Eigen::MatrixXd::ColXpr | getJointTrajectory (int joint) |
size_t | getNumPoints () const |
Gets the number of points in the trajectory. | |
size_t | getNumFreePoints () const |
Gets the number of points (that are free to be optimized) in the trajectory. | |
size_t | getNumJoints () const |
Gets the number of joints in each trajectory point. | |
double | getDiscretization () const |
Gets the discretization time interval of 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. | |
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.g., trajectory produced by OMPL) and puts it into the appropriate trajectory format required for CHOMP. | |
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 | setStartEndIndex (size_t start_index, size_t end_index) |
Sets the start and end index for the modifiable part of the trajectory. | |
size_t | getStartIndex () const |
Gets the start index. | |
size_t | getEndIndex () const |
Gets the end index. | |
Eigen::MatrixXd & | getTrajectory () |
Gets the entire trajectory matrix. | |
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > | getFreeTrajectoryBlock () |
Gets the block of the trajectory which can be optimized. | |
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > | getFreeJointTrajectoryBlock (size_t joint) |
Gets the block of free (optimizable) trajectory for a single joint. | |
void | updateFromGroupTrajectory (const ChompTrajectory &group_trajectory) |
Updates the full trajectory (*this) from the group trajectory. | |
size_t | getFullTrajectoryIndex (size_t i) const |
Gets the index in the full trajectory which was copied to this group trajectory. | |
template<typename Derived > | |
void | getJointVelocities (size_t traj_point, Eigen::MatrixBase< Derived > &velocities) |
Gets the joint velocities at the given trajectory point. | |
double | getDuration () const |
Represents a discretized joint-space trajectory for CHOMP.
Definition at line 53 of file chomp_trajectory.h.
chomp::ChompTrajectory::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.
Definition at line 41 of file chomp_trajectory.cpp.
chomp::ChompTrajectory::ChompTrajectory | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
size_t | num_points, | ||
double | discretization, | ||
const std::string & | group_name | ||
) |
Constructs a trajectory for a given robot model, number of trajectory points, and discretization.
Definition at line 47 of file chomp_trajectory.cpp.
chomp::ChompTrajectory::ChompTrajectory | ( | const ChompTrajectory & | source_traj, |
const std::string & | group_name, | ||
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 61 of file chomp_trajectory.cpp.
chomp::ChompTrajectory::ChompTrajectory | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
const std::string & | group_name, | ||
const trajectory_msgs::msg::JointTrajectory & | traj | ||
) |
|
virtualdefault |
Destructor.
void chomp::ChompTrajectory::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.
source | The source RobotState |
chomp_trajectory_point | index of the chomp_trajectory's point (row) |
group | JointModelGroup determining the joints to copy |
Definition at line 211 of file chomp_trajectory.cpp.
void chomp::ChompTrajectory::fillInCubicInterpolation | ( | ) |
Generates a cubic interpolation of the trajectory from the start index to end index.
Only modifies points from start_index_ to end_index_, inclusive
Definition at line 120 of file chomp_trajectory.cpp.
bool chomp::ChompTrajectory::fillInFromTrajectory | ( | const robot_trajectory::RobotTrajectory & | trajectory | ) |
Receives the path obtained from a given MotionPlanDetailedResponse res object's trajectory (e.g., trajectory produced by OMPL) and puts it into the appropriate trajectory format required for CHOMP.
res |
Definition at line 188 of file chomp_trajectory.cpp.
void chomp::ChompTrajectory::fillInLinearInterpolation | ( | ) |
Generates a linearly interpolated trajectory from the start index to end index.
Only modifies points from start_index_ to end_index_, inclusive
Definition at line 106 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 142 of file chomp_trajectory.cpp.
|
inline |
Gets the discretization time interval of the trajectory.
Definition at line 250 of file chomp_trajectory.h.
|
inline |
Definition at line 304 of file chomp_trajectory.h.
|
inline |
Gets the end index.
Definition at line 266 of file chomp_trajectory.h.
|
inline |
Gets the block of free (optimizable) trajectory for a single joint.
Definition at line 282 of file chomp_trajectory.h.
|
inline |
Gets the block of the trajectory which can be optimized.
Definition at line 276 of file chomp_trajectory.h.
|
inline |
Gets the index in the full trajectory which was copied to this group trajectory.
Definition at line 287 of file chomp_trajectory.h.
|
inline |
Definition at line 230 of file chomp_trajectory.h.
void chomp::ChompTrajectory::getJointVelocities | ( | size_t | traj_point, |
Eigen::MatrixBase< Derived > & | velocities | ||
) |
Gets the joint velocities at the given trajectory point.
Definition at line 293 of file chomp_trajectory.h.
|
inline |
Gets the number of points (that are free to be optimized) in the trajectory.
Definition at line 240 of file chomp_trajectory.h.
|
inline |
Gets the number of joints in each trajectory point.
Definition at line 245 of file chomp_trajectory.h.
|
inline |
Gets the number of points in the trajectory.
Definition at line 235 of file chomp_trajectory.h.
|
inline |
Gets the start index.
Definition at line 261 of file chomp_trajectory.h.
|
inline |
Gets the entire trajectory matrix.
Definition at line 271 of file chomp_trajectory.h.
|
inline |
|
inline |
Definition at line 215 of file chomp_trajectory.h.
|
inline |
Definition at line 220 of file chomp_trajectory.h.
|
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 255 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 99 of file chomp_trajectory.cpp.