chomp_trajectory.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Mrinal Kalakrishnan */
36 
37 #include <ros/ros.h>
39 
40 namespace chomp
41 {
42 ChompTrajectory::ChompTrajectory(const moveit::core::RobotModelConstPtr& robot_model, double duration,
43  double discretization, const std::string& group_name)
44  : ChompTrajectory(robot_model, static_cast<size_t>(duration / discretization) + 1, discretization, group_name)
45 {
46 }
47 
48 ChompTrajectory::ChompTrajectory(const moveit::core::RobotModelConstPtr& robot_model, size_t num_points,
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)
54  , start_index_(1)
55  , end_index_(num_points_ - 2)
56 {
57  const moveit::core::JointModelGroup* model_group = robot_model->getJointModelGroup(planning_group_name_);
58  num_joints_ = model_group->getActiveJointModels().size();
59  init();
60 }
61 
62 ChompTrajectory::ChompTrajectory(const ChompTrajectory& source_traj, const std::string& group_name, int diff_rule_length)
63  : planning_group_name_(group_name), discretization_(source_traj.discretization_)
64 {
65  num_joints_ = source_traj.getNumJoints();
66 
67  // figure out the num_points_:
68  // we need diff_rule_length-1 extra points on either side:
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_);
71 
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_;
76 
77  // allocate the memory:
78  init();
79 
80  full_trajectory_index_.resize(num_points_);
81 
82  // now copy the trajectories over:
83  for (size_t i = 0; i < num_points_; i++)
84  {
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);
92  }
93 }
94 
96 {
98 }
99 
101 {
102  size_t num_vars_free = end_index_ - start_index_ + 1;
103  trajectory_.block(start_index_, 0, num_vars_free, num_joints_) =
104  group_trajectory.trajectory_.block(group_trajectory.start_index_, 0, num_vars_free, num_joints_);
105 }
106 
108 {
109  double start_index = start_index_ - 1;
110  double end_index = end_index_ + 1;
111  for (size_t i = 0; i < num_joints_; i++)
112  {
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++)
115  {
116  (*this)(j, i) = (*this)(start_index, i) + j * theta;
117  }
118  }
119 }
120 
122 {
123  double start_index = start_index_ - 1;
124  double end_index = end_index_ + 1;
125  double dt = 0.001;
126  std::vector<double> coeffs(4, 0);
127  double total_time = (end_index - 1) * dt;
128  for (size_t i = 0; i < num_joints_; i++)
129  {
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));
133 
134  double t;
135  for (size_t j = start_index + 1; j < end_index; j++)
136  {
137  t = j * dt;
138  (*this)(j, i) = coeffs[0] + coeffs[2] * pow(t, 2) + coeffs[3] * pow(t, 3);
139  }
140  }
141 }
142 
144 {
145  double start_index = start_index_ - 1;
146  double end_index = end_index_ + 1;
147  double td[6]; // powers of the time duration
148  td[0] = 1.0;
149  td[1] = (end_index - start_index) * discretization_;
150 
151  for (unsigned int i = 2; i <= 5; i++)
152  td[i] = td[i - 1] * td[1];
153 
154  // calculate the spline coefficients for each joint:
155  // (these are for the special case of zero start and end vel and acc)
156  std::vector<double[6]> coeff(num_joints_);
157  for (size_t i = 0; i < num_joints_; i++)
158  {
159  double x0 = (*this)(start_index, i);
160  double x1 = (*this)(end_index, i);
161  coeff[i][0] = x0;
162  coeff[i][1] = 0;
163  coeff[i][2] = 0;
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]);
167  }
168 
169  // now fill in the joint positions at each time step
170  for (size_t i = start_index + 1; i < end_index; i++)
171  {
172  double ti[6]; // powers of the time index point
173  ti[0] = 1.0;
174  ti[1] = (i - start_index) * discretization_;
175  for (unsigned int k = 2; k <= 5; k++)
176  ti[k] = ti[k - 1] * ti[1];
177 
178  for (size_t j = 0; j < num_joints_; j++)
179  {
180  (*this)(i, j) = 0.0;
181  for (unsigned int k = 0; k <= 5; k++)
182  {
183  (*this)(i, j) += ti[k] * coeff[j][k];
184  }
185  }
186  }
187 }
188 
190 {
191  // check if input trajectory has less than two states (start and goal), function returns false if condition is true
192  if (trajectory.getWayPointCount() < 2)
193  return false;
194 
195  const size_t max_output_index = getNumPoints() - 1;
196  const size_t max_input_index = trajectory.getWayPointCount() - 1;
197 
198  const moveit::core::JointModelGroup* group = trajectory.getGroup();
199  moveit::core::RobotState interpolated(trajectory.getRobotModel());
200  for (size_t i = 0; i <= max_output_index; i++)
201  {
202  double fraction = static_cast<double>(i * max_input_index) / max_output_index;
203  const size_t prev_idx = std::trunc(fraction); // integer part
204  fraction = fraction - prev_idx; // fractional part
205  const size_t next_idx = prev_idx == max_input_index ? prev_idx : prev_idx + 1;
206  trajectory.getWayPoint(prev_idx).interpolate(trajectory.getWayPoint(next_idx), fraction, interpolated, group);
207  assignCHOMPTrajectoryPointFromRobotState(interpolated, i, group);
208  }
209  return true;
210 }
211 
213  size_t chomp_trajectory_point_index,
214  const moveit::core::JointModelGroup* group)
215 {
216  Eigen::MatrixXd::RowXpr target = getTrajectoryPoint(chomp_trajectory_point_index);
217  assert(group->getActiveJointModels().size() == static_cast<size_t>(target.cols()));
218  size_t joint_index = 0;
219  for (const moveit::core::JointModel* jm : group->getActiveJointModels())
220  {
221  assert(jm->getVariableCount() == 1);
222  target[joint_index++] = source.getVariablePosition(jm->getFirstVariableIndex());
223  }
224 }
225 
226 } // namespace chomp
chomp::ChompTrajectory
Represents a discretized joint-space trajectory for CHOMP.
Definition: chomp_trajectory.h:86
moveit::core::JointModelGroup::getActiveJointModels
const std::vector< const JointModel * > & getActiveJointModels() const
chomp::ChompTrajectory::fillInCubicInterpolation
void fillInCubicInterpolation()
Generates a cubic interpolation of the trajectory from the start index to end index.
Definition: chomp_trajectory.cpp:153
robot_trajectory::RobotTrajectory::getWayPointCount
std::size_t getWayPointCount() const
robot_trajectory::RobotTrajectory::getGroup
const moveit::core::JointModelGroup * getGroup() const
chomp::ChompTrajectory::updateFromGroupTrajectory
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
Definition: chomp_trajectory.cpp:132
chomp::ChompTrajectory::start_index_
size_t start_index_
Definition: chomp_trajectory.h:273
duration
std::chrono::system_clock::duration duration
chomp::ChompTrajectory::fillInFromTrajectory
bool fillInFromTrajectory(const robot_trajectory::RobotTrajectory &trajectory)
Receives the path obtained from a given MotionPlanDetailedResponse res object's trajectory (e....
Definition: chomp_trajectory.cpp:221
chomp::ChompTrajectory::end_index_
size_t end_index_
Definition: chomp_trajectory.h:274
robot_trajectory::RobotTrajectory::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
chomp::ChompTrajectory::num_points_
size_t num_points_
Definition: chomp_trajectory.h:268
chomp::ChompTrajectory::getTrajectoryPoint
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
Definition: chomp_trajectory.h:258
ros.h
chomp::ChompTrajectory::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: chomp_trajectory.cpp:74
chomp
Definition: chomp_cost.h:43
moveit::core::RobotState
robot_trajectory::RobotTrajectory
chomp_trajectory.h
moveit::core::RobotState::getVariablePosition
double getVariablePosition(const std::string &variable) const
chomp::ChompTrajectory::init
void init()
Allocates memory for the trajectory.
Definition: chomp_trajectory.cpp:127
chomp::ChompTrajectory::assignCHOMPTrajectoryPointFromRobotState
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.
Definition: chomp_trajectory.cpp:244
chomp::ChompTrajectory::getNumPoints
size_t getNumPoints() const
Gets the number of points in the trajectory.
Definition: chomp_trajectory.h:268
chomp::ChompTrajectory::fillInMinJerk
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
Definition: chomp_trajectory.cpp:175
moveit::core::RobotState::interpolate
void interpolate(const RobotState &to, double t, RobotState &state) const
moveit::core::JointModelGroup
init
void init(const M_string &remappings)
chomp::ChompTrajectory::fillInLinearInterpolation
void fillInLinearInterpolation()
Generates a linearly interpolated trajectory from the start index to end index.
Definition: chomp_trajectory.cpp:139
chomp::ChompTrajectory::trajectory_
Eigen::MatrixXd trajectory_
Definition: chomp_trajectory.h:272
chomp::ChompTrajectory::discretization_
double discretization_
Definition: chomp_trajectory.h:270
chomp::ChompTrajectory::num_joints_
size_t num_joints_
Definition: chomp_trajectory.h:269
t
geometry_msgs::TransformStamped t
moveit::core::JointModel
robot_trajectory::RobotTrajectory::getWayPoint
const moveit::core::RobotState & getWayPoint(std::size_t index) const


chomp_motion_planner
Author(s): Gil Jones , Mrinal Kalakrishnan
autogenerated on Sat Mar 15 2025 02:26:05