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 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 
00035 /* Author: Mrinal Kalakrishnan */
00036 
00037 #ifndef CHOMP_UTILS_H_
00038 #define CHOMP_UTILS_H_
00039 
00040 #include <iostream>
00041 #include <Eigen/Core>
00042 #include <moveit/planning_scene/planning_scene.h>
00043 
00044 namespace chomp
00045 {
00046 static const int DIFF_RULE_LENGTH = 7;
00047 
00048 // the differentiation rules (centered at the center)
00049 static const double DIFF_RULES[3][DIFF_RULE_LENGTH] = {
00050   { 0, 0, -2 / 6.0, -3 / 6.0, 6 / 6.0, -1 / 6.0, 0 },                       // velocity
00051   { 0, -1 / 12.0, 16 / 12.0, -30 / 12.0, 16 / 12.0, -1 / 12.0, 0 },         // acceleration
00052   { 0, 1 / 12.0, -17 / 12.0, 46 / 12.0, -46 / 12.0, 17 / 12.0, -1 / 12.0 }  // jerk
00053 };
00054 
00055 static inline void jointStateToArray(const moveit::core::RobotModelConstPtr& kmodel,
00056                                      const sensor_msgs::JointState& joint_state, const std::string& planning_group_name,
00057                                      Eigen::MatrixXd::RowXpr joint_array)
00058 {
00059   const moveit::core::JointModelGroup* group = kmodel->getJointModelGroup(planning_group_name);
00060   std::vector<const moveit::core::JointModel*> models = group->getActiveJointModels();
00061 
00062   for (unsigned int i = 0; i < joint_state.position.size(); i++)
00063   {
00064     for (size_t j = 0; j < models.size(); j++)
00065     {
00066       if (models[j]->getName() == joint_state.name[i])
00067       {
00068         joint_array(0, j) = joint_state.position[i];
00069       }
00070     }
00071   }
00072 }
00073 
00074 // copied from geometry/angles/angles.h
00075 static inline double normalizeAnglePositive(double angle)
00076 {
00077   return fmod(fmod(angle, 2.0 * M_PI) + 2.0 * M_PI, 2.0 * M_PI);
00078 }
00079 
00080 static inline double normalizeAngle(double angle)
00081 {
00082   double a = normalizeAnglePositive(angle);
00083   if (a > M_PI)
00084     a -= 2.0 * M_PI;
00085   return a;
00086 }
00087 
00088 static inline double shortestAngularDistance(double start, double end)
00089 {
00090   double res = normalizeAnglePositive(normalizeAnglePositive(end) - normalizeAnglePositive(start));
00091   if (res > M_PI)
00092   {
00093     res = -(2.0 * M_PI - res);
00094   }
00095   return normalizeAngle(res);
00096 }
00097 
00098 }  // namespace chomp
00099 
00100 #endif /* CHOMP_UTILS_H_ */


chomp_motion_planner
Author(s): Gil Jones
autogenerated on Mon Jul 24 2017 02:21:07