chomp_cost.h
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 #ifndef CHOMP_COST_H_
38 #define CHOMP_COST_H_
39 
40 #include <eigen3/Eigen/Core>
42 #include <vector>
43 
44 namespace chomp
45 {
49 class ChompCost
50 {
51 public:
52  ChompCost(const ChompTrajectory& trajectory, int joint_number, const std::vector<double>& derivative_costs,
53  double ridge_factor = 0.0);
54  virtual ~ChompCost();
55 
56  template <typename Derived>
57  void getDerivative(Eigen::MatrixXd::ColXpr joint_trajectory, Eigen::MatrixBase<Derived>& derivative) const;
58 
59  const Eigen::MatrixXd& getQuadraticCostInverse() const;
60 
61  const Eigen::MatrixXd& getQuadraticCost() const;
62 
63  double getCost(Eigen::MatrixXd::ColXpr joint_trajectory) const;
64 
65  double getMaxQuadCostInvValue() const;
66 
67  void scale(double scale);
68 
69 private:
70  Eigen::MatrixXd quad_cost_full_;
71  Eigen::MatrixXd quad_cost_;
72  // Eigen::VectorXd linear_cost_;
73  Eigen::MatrixXd quad_cost_inv_;
74 
75  Eigen::MatrixXd getDiffMatrix(int size, const double* diff_rule) const;
76 };
77 
78 template <typename Derived>
79 void ChompCost::getDerivative(Eigen::MatrixXd::ColXpr joint_trajectory, Eigen::MatrixBase<Derived>& derivative) const
80 {
81  derivative = (quad_cost_full_ * (2.0 * joint_trajectory));
82 }
83 
84 inline const Eigen::MatrixXd& ChompCost::getQuadraticCostInverse() const
85 {
86  return quad_cost_inv_;
87 }
88 
89 inline const Eigen::MatrixXd& ChompCost::getQuadraticCost() const
90 {
91  return quad_cost_;
92 }
93 
94 inline double ChompCost::getCost(Eigen::MatrixXd::ColXpr joint_trajectory) const
95 {
96  return joint_trajectory.dot(quad_cost_full_ * joint_trajectory);
97 }
98 
99 } // namespace chomp
100 
101 #endif /* CHOMP_COST_H_ */
virtual ~ChompCost()
Definition: chomp_cost.cpp:104
double getCost(Eigen::MatrixXd::ColXpr joint_trajectory) const
Definition: chomp_cost.h:94
double getMaxQuadCostInvValue() const
Definition: chomp_cost.cpp:91
const Eigen::MatrixXd & getQuadraticCostInverse() const
Definition: chomp_cost.h:84
ChompCost(const ChompTrajectory &trajectory, int joint_number, const std::vector< double > &derivative_costs, double ridge_factor=0.0)
Definition: chomp_cost.cpp:46
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
Represents the smoothness cost for CHOMP, for a single joint.
Definition: chomp_cost.h:49
void scale(double scale)
Definition: chomp_cost.cpp:96
const Eigen::MatrixXd & getQuadraticCost() const
Definition: chomp_cost.h:89
void getDerivative(Eigen::MatrixXd::ColXpr joint_trajectory, Eigen::MatrixBase< Derived > &derivative) const
Definition: chomp_cost.h:79
Represents a discretized joint-space trajectory for CHOMP.
Eigen::MatrixXd getDiffMatrix(int size, const double *diff_rule) const
Definition: chomp_cost.cpp:73
Eigen::MatrixXd quad_cost_inv_
Definition: chomp_cost.h:73
Eigen::MatrixXd quad_cost_
Definition: chomp_cost.h:71
Eigen::MatrixXd quad_cost_full_
Definition: chomp_cost.h:70


chomp_motion_planner
Author(s): Gil Jones , Mrinal Kalakrishnan
autogenerated on Sun Oct 18 2020 13:17:08