40 #include <planning_models/robot_model.h> 
   45 static inline bool loadLinkBodySphereDecompositions(
 
   46     ros::NodeHandle& nh, 
const planning_models::RobotModelConstPtr& robot_model,
 
   47     std::map<std::string, std::vector<collision_detection::CollisionSphere> >& link_body_spheres)
 
   49   if (!nh.hasParam(
"link_spheres"))
 
   51     ROS_INFO_STREAM(
"No parameter for link spheres");
 
   54   XmlRpc::XmlRpcValue link_spheres;
 
   55   nh.getParam(
"link_spheres", link_spheres);
 
   57   if (link_spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
 
   59     ROS_WARN_STREAM(
"Link spheres not an array");
 
   63   if (link_spheres.size() == 0)
 
   65     ROS_WARN_STREAM(
"Link spheres has no entries");
 
   68   for (
int i = 0; i < link_spheres.size(); ++i)
 
   70     if (!link_spheres[i].hasMember(
"link"))
 
   72       ROS_WARN_STREAM(
"All link spheres must have link");
 
   75     if (!link_spheres[i].hasMember(
"spheres"))
 
   77       ROS_WARN_STREAM(
"All link spheres must have spheres");
 
   80     std::string link = link_spheres[i][
"link"];
 
   81     XmlRpc::XmlRpcValue spheres = link_spheres[i][
"spheres"];
 
   82     if (spheres.getType() != XmlRpc::XmlRpcValue::TypeArray)
 
   84       if (std::string(spheres) == 
"none")
 
   86         ROS_DEBUG_STREAM(
"No spheres for " << link);
 
   87         std::vector<collision_detection::CollisionSphere> coll_spheres;
 
   88         link_body_spheres[link_spheres[i][
"link"]] = coll_spheres;
 
   92     std::vector<collision_detection::CollisionSphere> coll_spheres;
 
   93     for (
int j = 0; j < spheres.size(); ++j)
 
   95       if (!spheres[j].hasMember(
"x"))
 
   97         ROS_WARN_STREAM(
"All spheres must specify a value for x");
 
  100       if (!spheres[j].hasMember(
"y"))
 
  102         ROS_WARN_STREAM(
"All spheres must specify a value for y");
 
  105       if (!spheres[j].hasMember(
"z"))
 
  107         ROS_WARN_STREAM(
"All spheres must specify a value for z");
 
  110       if (!spheres[j].hasMember(
"radius"))
 
  112         ROS_WARN_STREAM(
"All spheres must specify a value for radius");
 
  115       Eigen::Vector3d rel(spheres[j][
"x"], spheres[j][
"y"], spheres[j][
"z"]);
 
  116       ROS_DEBUG_STREAM(
"Link " << link_spheres[i][
"link"] << 
" sphere " << coll_spheres.size() << 
" " << rel.x() << 
" " 
  117                                << rel.y() << 
" " << rel.z());
 
  119       coll_spheres.push_back(cs);
 
  121     link_body_spheres[link_spheres[i][
"link"]] = coll_spheres;
 
Vec3fX< details::Vec3Data< double > > Vector3d