chomp_utils.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00038 #ifndef CHOMP_UTILS_H_
00039 #define CHOMP_UTILS_H_
00040 
00041 #include <iostream>
00042 #include <Eigen/Core>
00043 #include <planning_scene/planning_scene.h>
00044 
00045 namespace chomp
00046 {
00047 
00048 static const int DIFF_RULE_LENGTH = 7;
00049 
00050 // the differentiation rules (centered at the center)
00051 static const double DIFF_RULES[3][DIFF_RULE_LENGTH] = {
00052     {0, 0, -2/6.0, -3/6.0, 6/6.0, -1/6.0, 0},                   // velocity
00053     {0, -1/12.0, 16/12.0, -30/12.0, 16/12.0, -1/12.0, 0},       // acceleration
00054     {0, 1/12.0, -17/12.0, 46/12.0, -46/12.0, 17/12.0, -1/12.0}  // jerk
00055 };
00056 
00057 static inline void jointStateToArray(const planning_models::RobotModelConstPtr& kmodel,
00058                               const sensor_msgs::JointState &joint_state,
00059                               const std::string& planning_group_name,
00060                               Eigen::MatrixXd::RowXpr joint_array)
00061 {
00062   const planning_models::RobotModel::JointModelGroup* group = kmodel->getJointModelGroup(planning_group_name);
00063   std::vector<const planning_models::RobotModel::JointModel*> models = group->getJointModels();
00064 
00065   for(unsigned int i=0; i < joint_state.position.size(); i++)
00066   {
00067     for(size_t j = 0; j < models.size(); j++)
00068     {
00069       if(models[j]->getName() == joint_state.name[i])
00070       {
00071         joint_array(0, j) = joint_state.position[i];
00072       }
00073     }
00074   }
00075 }
00076 
00077 //copied from geometry/angles/angles.h
00078 static inline double normalizeAnglePositive(double angle)
00079 {
00080   return fmod(fmod(angle, 2.0*M_PI) + 2.0*M_PI, 2.0*M_PI);
00081 }
00082 
00083 static inline double normalizeAngle(double angle)
00084 {
00085   double a = normalizeAnglePositive(angle);
00086   if (a > M_PI)
00087     a -= 2.0 *M_PI;
00088   return a;
00089 }
00090 
00091 static inline double shortestAngularDistance(double start, double end) {
00092   double res = normalizeAnglePositive(normalizeAnglePositive(end)-normalizeAnglePositive(start));
00093   if(res > M_PI) {
00094     res = -(2.0*M_PI-res);
00095   }
00096   return normalizeAngle(res);
00097 }
00098 
00099 } //namespace chomp
00100 
00101 #endif /* CHOMP_UTILS_H_ */


chomp_motion_planner
Author(s): Gil Jones
autogenerated on Mon Oct 6 2014 11:12:26