libmove3d-planners
 All Classes Namespaces Files Functions Variables Enumerations Enumerator Friends Macros Groups Pages
chompTrajectory.hpp
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 the 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 
37 #ifndef CHOMP_TRAJECTORY_H_
38 #define CHOMP_TRAJECTORY_H_
39 
40 //#include <trajectory_msgs/JointTrajectory.h>
41 
42 //#include <chomp_motion_planner/chomp_robot_model.h>
43 #include "API/Device/robot.hpp"
44 #include "API/Trajectory/trajectory.hpp"
45 
46 #include "chompUtils.hpp"
47 #include "chompPlanningGroup.hpp"
48 
49 #include <vector>
50 //#include <kdl/jntarray.hpp>
51 
52 #include <Eigen/Core>
53 
54 //namespace chomp
55 //{
56 
61 {
62 public:
63  ChompTrajectory() {}
67  ChompTrajectory(const API::Trajectory& T, int diff_rule_length, const ChompPlanningGroup& active_joints_);
68 
72  // ChompTrajectory(const ChompRobotModel* robot_model, int num_points, double discretization);
73 
78  ChompTrajectory(const ChompTrajectory& source_traj, int diff_rule_length);
79 
80  // ChompTrajectory(const ChompRobotModel* robot_model,
81  // const ChompRobotModel::ChompPlanningGroup* planning_group,
82  // const trajectory_msgs::JointTrajectory& traj);
83 
87  virtual ~ChompTrajectory();
88 
89  double& operator() (int traj_point, int joint);
90 
91  double operator() (int traj_point, int joint) const;
92 
93  Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point);
94 
95  //void getTrajectoryPointKDL(int traj_point, KDL::JntArray& kdl_jnt_array) const;
96  void getTrajectoryPointP3d(int traj_point, Eigen::VectorXd& jnt_array) const;
97 
98  Eigen::MatrixXd::ColXpr getJointTrajectory(int joint);
99 
100  //void overwriteTrajectory(const trajectory_msgs::JointTrajectory& traj);
101 
105  int getNumPoints() const;
106 
110  int getNumFreePoints() const;
111 
115  int getNumJoints() const;
116 
120  double getDiscretization() const;
121 
127  void fillInMinJerk();
128 
135  void setStartEndIndex(int start_index, int end_index);
136 
140  int getStartIndex() const;
141 
145  int getEndIndex() const;
146 
150  Eigen::MatrixXd& getTrajectory();
151 
155  Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic> getFreeTrajectoryBlock();
156 
160  Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic> getFreeJointTrajectoryBlock(int joint);
161 
165  void updateFromGroupTrajectory(const ChompTrajectory& group_trajectory);
166 
170  int getFullTrajectoryIndex(int i) const;
171 
175  template <typename Derived>
176  void getJointVelocities(int traj_point, Eigen::MatrixBase<Derived>& velocities);
177 
178  double getDuration() const;
179 
180  // Returns the Move3d robot
181  Robot* getRobot() { return robot_model_; }
182 
183  // prints the big matrix
184  void print();
185 
186 private:
187 
188  void init();
190  Robot* robot_model_;
191  // const ChompRobotModel* robot_model_; /**< Robot Model */
192  // const ChompRobotModel::ChompPlanningGroup* planning_group_; /**< Planning group that this trajectory corresponds to, if any */
193  int num_points_;
194  int num_joints_;
195  double discretization_;
196  double duration_;
197  Eigen::MatrixXd trajectory_;
198  int start_index_;
199  int end_index_;
200  std::vector<int> full_trajectory_index_;
201 };
202 
204 
205 inline double& ChompTrajectory::operator() (int traj_point, int joint)
206 {
207  return trajectory_(traj_point, joint);
208 }
209 
210 inline double ChompTrajectory::operator() (int traj_point, int joint) const
211 {
212  return trajectory_(traj_point, joint);
213 }
214 
215 inline Eigen::MatrixXd::RowXpr ChompTrajectory::getTrajectoryPoint(int traj_point)
216 {
217  return trajectory_.row(traj_point);
218 }
219 
220 inline Eigen::MatrixXd::ColXpr ChompTrajectory::getJointTrajectory(int joint)
221 {
222  return trajectory_.col(joint);
223 }
224 
226 {
227  return num_points_;
228 }
229 
231 {
232  return (end_index_ - start_index_)+1;
233 }
234 
236 {
237  return num_joints_;
238 }
239 
241 {
242  return discretization_;
243 }
244 
245 inline void ChompTrajectory::setStartEndIndex(int start_index, int end_index)
246 {
247  start_index_ = start_index;
248  end_index_ = end_index;
249 }
250 
252 {
253  return start_index_;
254 }
255 
257 {
258  return end_index_;
259 }
260 
261 inline Eigen::MatrixXd& ChompTrajectory::getTrajectory()
262 {
263  return trajectory_;
264 }
265 
266 inline Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic> ChompTrajectory::getFreeTrajectoryBlock()
267 {
268 // std::cout << "getNumFreePoints() = " << getNumFreePoints() << std::endl;
269 // std::cout << "getNumJoints() = " << getNumJoints() << std::endl;
270 
271  return trajectory_.block(start_index_, 0, getNumFreePoints(), getNumJoints());
272 }
273 
274 inline Eigen::Block<Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic> ChompTrajectory::getFreeJointTrajectoryBlock(int joint)
275 {
276  return trajectory_.block(start_index_, joint, getNumFreePoints(), 1);
277 }
278 
279 //inline void ChompTrajectory::getTrajectoryPointKDL(int traj_point, KDL::JntArray& kdl_jnt_array) const
280 //{
281 // for (int i=0; i<num_joints_; i++)
282 // kdl_jnt_array(i) = trajectory_(traj_point,i);
283 //}
284 
286 {
287  return full_trajectory_index_[i];
288 }
289 
290 template <typename Derived>
291 void ChompTrajectory::getJointVelocities(int traj_point, Eigen::MatrixBase<Derived>& velocities)
292 {
293  velocities.setZero();
294  double invTime = 1.0 / discretization_;
295 
296  for (int k=-DIFF_RULE_LENGTH/2; k<=DIFF_RULE_LENGTH/2; k++)
297  {
298  velocities += (invTime * DIFF_RULES[0][k+DIFF_RULE_LENGTH/2]) * trajectory_.row(traj_point+k).transpose();
299  }
300 }
301 
302 inline double ChompTrajectory::getDuration() const {
303  return duration_;
304 }
305 
306 //}
307 
308 #endif /* CHOMP_TRAJECTORY_H_ */
309 
310 
311 
312 
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
Definition: chompTrajectory.cpp:185
int getFullTrajectoryIndex(int i) const
Gets the index in the full trajectory which was copied to this group trajectory.
Definition: chompTrajectory.hpp:285
Contains information about a planning group.
Definition: chompPlanningGroup.hpp:38
int getStartIndex() const
Gets the start index.
Definition: chompTrajectory.hpp:251
void getJointVelocities(int traj_point, Eigen::MatrixBase< Derived > &velocities)
Gets the joint velocities at the given trajectory point.
Definition: chompTrajectory.hpp:291
int getEndIndex() const
Gets the end index.
Definition: chompTrajectory.hpp:256
Represents a discretized joint-space trajectory for CHOMP.
Definition: chompTrajectory.hpp:60
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.
Definition: chompTrajectory.hpp:266
virtual ~ChompTrajectory()
Destructor.
Definition: chompTrajectory.cpp:154
This class holds a the robot represented by a kinematic chain.
Definition: robot.hpp:42
int getNumPoints() const
Gets the number of points in the trajectory.
Definition: chompTrajectory.hpp:225
double getDiscretization() const
Gets the discretization time interval of the trajectory.
Definition: chompTrajectory.hpp:240
void setStartEndIndex(int start_index, int end_index)
Sets the start and end index for the modifiable part of the trajectory.
Definition: chompTrajectory.hpp:245
int getNumJoints() const
Gets the number of joints in each trajectory point.
Definition: chompTrajectory.hpp:235
Definition: trajectory.hpp:40
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
Definition: chompTrajectory.cpp:165
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
Definition: chompTrajectory.hpp:261
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeJointTrajectoryBlock(int joint)
Gets the block of free (optimizable) trajectory for a single joint.
Definition: chompTrajectory.hpp:274
int getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
Definition: chompTrajectory.hpp:230