42 double discretization,
const std::string& group_name)
43 :
ChompTrajectory(robot_model, static_cast<size_t>(duration / discretization) + 1, discretization, group_name)
48 double discretization,
const std::string& group_name)
49 : planning_group_name_(group_name)
50 , num_points_(num_points)
51 , discretization_(discretization)
52 , duration_((num_points - 1) * discretization)
54 , end_index_(num_points_ - 2)
62 : planning_group_name_(group_name), discretization_(source_traj.discretization_)
68 int start_extra = (diff_rule_length - 1) - source_traj.start_index_;
69 int end_extra = (diff_rule_length - 1) - ((source_traj.num_points_ - 1) - source_traj.end_index_);
71 num_points_ = source_traj.num_points_ + start_extra + end_extra;
72 start_index_ = diff_rule_length - 1;
73 end_index_ = (num_points_ - 1) - (diff_rule_length - 1);
74 duration_ = (num_points_ - 1) * discretization_;
79 full_trajectory_index_.resize(num_points_);
82 for (
size_t i = 0; i < num_points_; ++i)
84 int source_traj_point = i - start_extra;
85 if (source_traj_point < 0)
86 source_traj_point = 0;
87 if (
static_cast<size_t>(source_traj_point) >= source_traj.num_points_)
88 source_traj_point = source_traj.num_points_ - 1;
89 full_trajectory_index_[i] = source_traj_point;
94 void ChompTrajectory::init()
96 trajectory_.resize(num_points_, num_joints_);
101 size_t num_vars_free = end_index_ - start_index_ + 1;
102 trajectory_.block(start_index_, 0, num_vars_free, num_joints_) =
103 group_trajectory.trajectory_.block(group_trajectory.start_index_, 0, num_vars_free, num_joints_);
108 double start_index = start_index_ - 1;
109 double end_index = end_index_ + 1;
110 for (
size_t i = 0; i < num_joints_; ++i)
112 double theta = ((*this)(end_index, i) - (*
this)(start_index, i)) / (end_index - 1);
113 for (
size_t j = start_index + 1; j < end_index; ++j)
115 (*this)(j, i) = (*
this)(start_index, i) + j * theta;
122 double start_index = start_index_ - 1;
123 double end_index = end_index_ + 1;
125 std::vector<double> coeffs(4, 0);
126 double total_time = (end_index - 1) * dt;
127 for (
size_t i = 0; i < num_joints_; ++i)
129 coeffs[0] = (*this)(start_index, i);
130 coeffs[2] = (3 / (pow(total_time, 2))) * ((*this)(end_index, i) - (*
this)(start_index, i));
131 coeffs[3] = (-2 / (pow(total_time, 3))) * ((*this)(end_index, i) - (*
this)(start_index, i));
134 for (
size_t j = start_index + 1; j < end_index; ++j)
137 (*this)(j, i) = coeffs[0] + coeffs[2] * pow(t, 2) + coeffs[3] * pow(t, 3);
144 double start_index = start_index_ - 1;
145 double end_index = end_index_ + 1;
148 td[1] = (end_index - start_index) * discretization_;
150 for (
unsigned int i = 2; i <= 5; ++i)
151 td[i] = td[i - 1] * td[1];
155 std::vector<std::array<double, 6>> coeff(num_joints_);
156 for (
size_t i = 0; i < num_joints_; ++i)
158 double x0 = (*this)(start_index, i);
159 double x1 = (*this)(end_index, i);
163 coeff[i][3] = (-20 * x0 + 20 * x1) / (2 * td[3]);
164 coeff[i][4] = (30 * x0 - 30 * x1) / (2 * td[4]);
165 coeff[i][5] = (-12 * x0 + 12 * x1) / (2 * td[5]);
169 for (
size_t i = start_index + 1; i < end_index; ++i)
173 ti[1] = (i - start_index) * discretization_;
174 for (
unsigned int k = 2; k <= 5; ++k)
175 ti[k] = ti[k - 1] * ti[1];
177 for (
size_t j = 0; j < num_joints_; ++j)
180 for (
unsigned int k = 0; k <= 5; ++k)
182 (*this)(i, j) += ti[k] * coeff[j][k];
199 for (
size_t i = 0; i <= max_output_index; ++i)
201 double fraction =
static_cast<double>(i * max_input_index) / max_output_index;
202 const size_t prev_idx = std::trunc(
fraction);
204 const size_t next_idx = prev_idx == max_input_index ? prev_idx : prev_idx + 1;
212 size_t chomp_trajectory_point_index,
216 assert(
group->getActiveJointModels().size() ==
static_cast<size_t>(target.cols()));
217 size_t joint_index = 0;
220 assert(jm->getVariableCount() == 1);
Represents a discretized joint-space trajectory for CHOMP.
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.
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 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....
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
void fillInLinearInterpolation()
Generates a linearly interpolated trajectory from the start index to end index.
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void interpolate(const RobotState &to, double t, RobotState &state) const
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Maintain a sequence of waypoints and the time durations between these waypoints.
const moveit::core::RobotModelConstPtr & getRobotModel() const
const moveit::core::JointModelGroup * getGroup() const
std::size_t getWayPointCount() const
const moveit::core::RobotState & getWayPoint(std::size_t index) const