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
00037 #ifndef COLLISION_DISTANCE_FIELD_HELPERS_H_
00038 #define COLLISION_DISTANCE_FIELD_HELPERS_H_
00039
00040 #include <ros/ros.h>
00041 #include <planning_models/robot_model.h>
00042 #include <collision_distance_field/collision_distance_field_types.h>
00043
00044 namespace collision_detection
00045 {
00046 static inline bool loadLinkBodySphereDecompositions(
00047 ros::NodeHandle& nh, const planning_models::RobotModelConstPtr& kmodel,
00048 std::map<std::string, std::vector<collision_detection::CollisionSphere> >& link_body_spheres)
00049 {
00050 if (!nh.hasParam("link_spheres"))
00051 {
00052 ROS_INFO_STREAM("No parameter for link spheres");
00053 return false;
00054 }
00055 XmlRpc::XmlRpcValue link_spheres;
00056 nh.getParam("link_spheres", link_spheres);
00057
00058 if (link_spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
00059 {
00060 ROS_WARN_STREAM("Link spheres not an array");
00061 return false;
00062 }
00063
00064 if (link_spheres.size() == 0)
00065 {
00066 ROS_WARN_STREAM("Link spheres has no entries");
00067 return false;
00068 }
00069 for (int i = 0; i < link_spheres.size(); i++)
00070 {
00071 if (!link_spheres[i].hasMember("link"))
00072 {
00073 ROS_WARN_STREAM("All link spheres must have link");
00074 continue;
00075 }
00076 if (!link_spheres[i].hasMember("spheres"))
00077 {
00078 ROS_WARN_STREAM("All link spheres must have spheres");
00079 continue;
00080 }
00081 std::string link = link_spheres[i]["link"];
00082 XmlRpc::XmlRpcValue spheres = link_spheres[i]["spheres"];
00083 if (spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
00084 {
00085 if (std::string(spheres) == "none")
00086 {
00087 ROS_DEBUG_STREAM("No spheres for " << link);
00088 std::vector<collision_detection::CollisionSphere> coll_spheres;
00089 link_body_spheres[link_spheres[i]["link"]] = coll_spheres;
00090 continue;
00091 }
00092 }
00093 std::vector<collision_detection::CollisionSphere> coll_spheres;
00094 for (int j = 0; j < spheres.size(); j++)
00095 {
00096 if (!spheres[j].hasMember("x"))
00097 {
00098 ROS_WARN_STREAM("All spheres must specify a value for x");
00099 continue;
00100 }
00101 if (!spheres[j].hasMember("y"))
00102 {
00103 ROS_WARN_STREAM("All spheres must specify a value for y");
00104 continue;
00105 }
00106 if (!spheres[j].hasMember("z"))
00107 {
00108 ROS_WARN_STREAM("All spheres must specify a value for z");
00109 continue;
00110 }
00111 if (!spheres[j].hasMember("radius"))
00112 {
00113 ROS_WARN_STREAM("All spheres must specify a value for radius");
00114 continue;
00115 }
00116 Eigen::Vector3d rel(spheres[j]["x"], spheres[j]["y"], spheres[j]["z"]);
00117 ROS_DEBUG_STREAM("Link " << link_spheres[i]["link"] << " sphere " << coll_spheres.size() << " " << rel.x() << " "
00118 << rel.y() << " " << rel.z());
00119 collision_detection::CollisionSphere cs(rel, spheres[j]["radius"]);
00120 coll_spheres.push_back(cs);
00121 }
00122 link_body_spheres[link_spheres[i]["link"]] = coll_spheres;
00123
00124
00125 }
00126 return true;
00127 }
00128 }
00129 #endif