Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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
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},
00053 {0, -1/12.0, 16/12.0, -30/12.0, 16/12.0, -1/12.0, 0},
00054 {0, 1/12.0, -17/12.0, 46/12.0, -46/12.0, 17/12.0, -1/12.0}
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
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 }
00100
00101 #endif