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
00035
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
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 },
00051 { 0, -1 / 12.0, 16 / 12.0, -30 / 12.0, 16 / 12.0, -1 / 12.0, 0 },
00052 { 0, 1 / 12.0, -17 / 12.0, 46 / 12.0, -46 / 12.0, 17 / 12.0, -1 / 12.0 }
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
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 }
00099
00100 #endif