43 double discretization,
const std::string& group_name)
44 : ChompTrajectory(robot_model, static_cast<size_t>(
duration / discretization) + 1, discretization, group_name)
49 double discretization,
const std::string& group_name)
50 : planning_group_name_(group_name)
51 , num_points_(num_points)
52 , discretization_(discretization)
53 , duration_((num_points - 1) * discretization)
55 , end_index_(num_points_ - 2)
63 : planning_group_name_(group_name), discretization_(source_traj.discretization_)
65 num_joints_ = source_traj.getNumJoints();
69 int start_extra = (diff_rule_length - 1) - source_traj.start_index_;
70 int end_extra = (diff_rule_length - 1) - ((source_traj.num_points_ - 1) - source_traj.end_index_);
72 num_points_ = source_traj.num_points_ + start_extra + end_extra;
73 start_index_ = diff_rule_length - 1;
74 end_index_ = (num_points_ - 1) - (diff_rule_length - 1);
75 duration_ = (num_points_ - 1) * discretization_;
80 full_trajectory_index_.resize(num_points_);
83 for (
size_t i = 0; i < num_points_; i++)
85 int source_traj_point = i - start_extra;
86 if (source_traj_point < 0)
87 source_traj_point = 0;
88 if (
static_cast<size_t>(source_traj_point) >= source_traj.num_points_)
89 source_traj_point = source_traj.num_points_ - 1;
90 full_trajectory_index_[i] = source_traj_point;
91 getTrajectoryPoint(i) =
const_cast<ChompTrajectory&
>(source_traj).getTrajectoryPoint(source_traj_point);
113 double theta = ((*this)(end_index, i) - (*
this)(start_index, i)) / (end_index - 1);
114 for (
size_t j = start_index + 1; j < end_index; j++)
116 (*this)(j, i) = (*
this)(start_index, i) + j * theta;
126 std::vector<double> coeffs(4, 0);
127 double total_time = (end_index - 1) * dt;
130 coeffs[0] = (*this)(start_index, i);
131 coeffs[2] = (3 / (pow(total_time, 2))) * ((*this)(end_index, i) - (*
this)(start_index, i));
132 coeffs[3] = (-2 / (pow(total_time, 3))) * ((*this)(end_index, i) - (*
this)(start_index, i));
135 for (
size_t j = start_index + 1; j < end_index; j++)
138 (*this)(j, i) = coeffs[0] + coeffs[2] * pow(
t, 2) + coeffs[3] * pow(
t, 3);
151 for (
unsigned int i = 2; i <= 5; i++)
152 td[i] = td[i - 1] * td[1];
159 double x0 = (*this)(start_index, i);
160 double x1 = (*this)(end_index, i);
164 coeff[i][3] = (-20 * x0 + 20 * x1) / (2 * td[3]);
165 coeff[i][4] = (30 * x0 - 30 * x1) / (2 * td[4]);
166 coeff[i][5] = (-12 * x0 + 12 * x1) / (2 * td[5]);
170 for (
size_t i = start_index + 1; i < end_index; i++)
175 for (
unsigned int k = 2; k <= 5; k++)
176 ti[k] = ti[k - 1] * ti[1];
181 for (
unsigned int k = 0; k <= 5; k++)
183 (*this)(i, j) += ti[k] * coeff[j][k];
200 for (
size_t i = 0; i <= max_output_index; i++)
202 double fraction =
static_cast<double>(i * max_input_index) / max_output_index;
203 const size_t prev_idx = std::trunc(fraction);
204 fraction = fraction - prev_idx;
205 const size_t next_idx = prev_idx == max_input_index ? prev_idx : prev_idx + 1;
213 size_t chomp_trajectory_point_index,
218 size_t joint_index = 0;
221 assert(jm->getVariableCount() == 1);