2 #include <boost/filesystem/operations.hpp> 
    6 #include "urdf_parser/urdf_parser.h" 
    8 #include <kdl/frames_io.hpp> 
   13 using namespace boost;
 
   14 using namespace boost::filesystem;
 
   20   geometry_msgs::Transform 
Pose2Transform( 
const geometry_msgs::Pose pose_msg){
 
   21     geometry_msgs::Transform tf_msg;
 
   22     tf_msg.translation.x = pose_msg.position.x;
 
   23     tf_msg.translation.y = pose_msg.position.y;
 
   24     tf_msg.translation.z = pose_msg.position.z;
 
   25     tf_msg.rotation = pose_msg.orientation;
 
   30     geometry_msgs::Pose pose_msg;
 
   31     pose_msg.position.x =  tf_msg.translation.x;
 
   32     pose_msg.position.y = tf_msg.translation.y;
 
   33     pose_msg.position.z = tf_msg.translation.z;
 
   34     pose_msg.orientation = tf_msg.rotation;
 
   39     geometry_msgs::Pose p_msg;
 
   41     pose.rotation.getQuaternion(
x,
y,
z,
w);
 
   42     p_msg.orientation.x = 
x;
 
   43     p_msg.orientation.y = 
y;
 
   44     p_msg.orientation.z = 
z;
 
   45     p_msg.orientation.w = 
w;
 
   47     p_msg.position.x = 
pose.position.x;
 
   48     p_msg.position.y = 
pose.position.y;
 
   49     p_msg.position.z = 
pose.position.z;
 
   55   visualization_msgs::InteractiveMarkerControl 
makeCylinderMarkerControl(
const geometry_msgs::PoseStamped &stamped, 
double length,  
double radius, 
const std_msgs::ColorRGBA &color, 
bool use_color){
 
   56     visualization_msgs::Marker cylinderMarker;
 
   58     if (use_color) cylinderMarker.color = color;
 
   59     cylinderMarker.type = visualization_msgs::Marker::CYLINDER;
 
   60     cylinderMarker.scale.x = 
radius * 2;
 
   61     cylinderMarker.scale.y = 
radius * 2;
 
   62     cylinderMarker.scale.z = 
length;
 
   63     cylinderMarker.pose = stamped.pose;
 
   65     visualization_msgs::InteractiveMarkerControl control;
 
   66     control.markers.push_back( cylinderMarker );
 
   67     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
   68     control.always_visible = 
true;
 
   73   visualization_msgs::InteractiveMarkerControl 
makeBoxMarkerControl(
const geometry_msgs::PoseStamped &stamped, Vector3 dim, 
const std_msgs::ColorRGBA &color, 
bool use_color){
 
   74     visualization_msgs::Marker boxMarker;
 
   76     fprintf(
stderr, 
"urdfModelMarker = %f %f %f\n", dim.x, dim.y, dim.z);
 
   77     if (use_color) boxMarker.color = color;
 
   78     boxMarker.type = visualization_msgs::Marker::CUBE;
 
   79     boxMarker.scale.x = dim.x;
 
   80     boxMarker.scale.y = dim.y;
 
   81     boxMarker.scale.z = dim.z;
 
   82     boxMarker.pose = stamped.pose;
 
   84     visualization_msgs::InteractiveMarkerControl control;
 
   85     control.markers.push_back( boxMarker );
 
   86     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
   87     control.always_visible = 
true;
 
   92   visualization_msgs::InteractiveMarkerControl 
makeSphereMarkerControl(
const geometry_msgs::PoseStamped &stamped, 
double rad, 
const std_msgs::ColorRGBA &color, 
bool use_color){
 
   93     visualization_msgs::Marker sphereMarker;
 
   95     if (use_color) sphereMarker.color = color;
 
   96     sphereMarker.type = visualization_msgs::Marker::SPHERE;
 
   97     sphereMarker.scale.x = rad * 2;
 
   98     sphereMarker.scale.y = rad * 2;
 
   99     sphereMarker.scale.z = rad * 2;
 
  100     sphereMarker.pose = stamped.pose;
 
  102     visualization_msgs::InteractiveMarkerControl control;
 
  103     control.markers.push_back( sphereMarker );
 
  104     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  105     control.always_visible = 
true;
 
  112   visualization_msgs::InteractiveMarkerControl 
makeMeshMarkerControl(
const std::string &mesh_resource, 
const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, 
const std_msgs::ColorRGBA &color, 
bool use_color){
 
  113     visualization_msgs::Marker meshMarker;
 
  115     if (use_color) meshMarker.color = color;
 
  117     meshMarker.mesh_use_embedded_materials = !use_color;
 
  118     meshMarker.type = visualization_msgs::Marker::MESH_RESOURCE;
 
  120     meshMarker.scale = 
scale;
 
  121     meshMarker.pose = stamped.pose;
 
  122     visualization_msgs::InteractiveMarkerControl control;
 
  123     control.markers.push_back( meshMarker );
 
  124     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  125     control.always_visible = 
true;
 
  130   visualization_msgs::InteractiveMarkerControl 
makeMeshMarkerControl(
const std::string &mesh_resource, 
const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale)
 
  132     std_msgs::ColorRGBA color;
 
  141                                                                      const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, 
const std_msgs::ColorRGBA &color)
 
  151     if(!
root && link->parent_joint){
 
  152       KDL::Frame parent_to_joint_frame;
 
  153       geometry_msgs::Pose parent_to_joint_pose = 
UrdfPose2Pose(link->parent_joint->parent_to_joint_origin_transform);
 
  155       previous_frame =  previous_frame * parent_to_joint_frame;
 
  163     geometry_msgs::PoseStamped ps;
 
  165     std::vector<VisualSharedPtr> visual_array;
 
  166     if(link->visual_array.size() != 0){
 
  167       visual_array = link->visual_array;
 
  168     }
else if(link->visual.get() != 
NULL){
 
  169       visual_array.push_back(link->visual);
 
  171     for(
int i=0; 
i<visual_array.size(); 
i++){
 
  173       if(link_visual.get() != 
NULL && link_visual->geometry.get() != 
NULL){
 
  174         visualization_msgs::InteractiveMarkerControl meshControl;
 
  175         if(link_visual->geometry->type == Geometry::MESH){
 
  176 #if ROS_VERSION_MINIMUM(1,14,0) // melodic 
  177           MeshConstSharedPtr mesh = std::static_pointer_cast<const Mesh>(link_visual->geometry);
 
  179         MeshConstSharedPtr mesh = boost::static_pointer_cast<const Mesh>(link_visual->geometry);
 
  181           string model_mesh_ = mesh->filename;
 
  185           KDL::Frame pose_frame, origin_frame;
 
  188           pose_frame =  previous_frame * origin_frame;
 
  189           geometry_msgs::Pose 
pose;
 
  193           cout << 
"mesh_file:" << model_mesh_ << endl;
 
  195           geometry_msgs::Vector3 mesh_scale;
 
  196           mesh_scale.x = mesh->scale.x * 
scale;
 
  197           mesh_scale.y = mesh->scale.y * 
scale;
 
  198           mesh_scale.z = mesh->scale.z * 
scale;
 
  204         }
else if(link_visual->geometry->type == Geometry::CYLINDER){
 
  205 #if ROS_VERSION_MINIMUM(1,14,0) // melodic 
  210           std::cout << 
"cylinder " << link->name;
 
  212           double length = cylinder->length;
 
  213           double radius = cylinder->radius;
 
  214           std::cout << 
", length =  " << 
length << 
", radius " << 
radius << std::endl;
 
  220         }
else if(link_visual->geometry->type == Geometry::BOX){
 
  221 #if ROS_VERSION_MINIMUM(1,14,0) // melodic 
  222     BoxConstSharedPtr box = std::static_pointer_cast<const Box>(link_visual->geometry);
 
  224     BoxConstSharedPtr box = boost::static_pointer_cast<const Box>(link_visual->geometry);
 
  226           std::cout << 
"box " << link->name;
 
  228           Vector3 dim = box->dim;
 
  229           std::cout << 
", dim =  " << dim.x << 
", " << dim.y << 
", " << dim.z << std::endl;
 
  235         }
else if(link_visual->geometry->type == Geometry::SPHERE){
 
  236 #if ROS_VERSION_MINIMUM(1,14,0) // melodic 
  242           double rad = sphere->radius;
 
  249         im.controls.push_back( meshControl );
 
  253     for (std::vector<LinkSharedPtr>::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++){
 
  263     std::fstream xml_file(model_file.c_str(), std::fstream::in);
 
  264     while ( xml_file.good() )
 
  267         std::getline( xml_file, 
line);
 
  272     std::cout << 
"model_file:" << model_file << std::endl;
 
  275       std::cerr << 
"ERROR: Model Parsing the xml failed" << std::endl;
 
  281   visualization_msgs::InteractiveMarker 
makeLinksMarker(
LinkConstSharedPtr link, 
bool use_color, std_msgs::ColorRGBA color, geometry_msgs::PoseStamped marker_ps, geometry_msgs::Pose origin_pose)
 
  283     visualization_msgs::InteractiveMarker int_marker;
 
  284     int_marker.header = marker_ps.header;
 
  285     int_marker.pose = marker_ps.pose;
 
  287     int_marker.name = 
"sample";
 
  288     int_marker.scale = 1.0;
 
  290     KDL::Frame origin_frame;
 
  300     visualization_msgs::InteractiveMarker int_marker;
 
  301     int_marker.name = name;
 
  302     int_marker.header = ps.header;
 
  303     int_marker.pose = ps.pose;
 
  304     int_marker.scale = 0.5;
 
  306     visualization_msgs::InteractiveMarkerControl control;
 
  309     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  310     control.orientation.w = 1;
 
  311     control.orientation.x = 0;
 
  312     control.orientation.y = 0;
 
  313     control.orientation.z = 1;
 
  315     int_marker.controls.push_back(control);
 
  384     visualization_msgs::InteractiveMarker int_marker;
 
  385     int_marker.header = ps.header;
 
  386     int_marker.pose = ps.pose;
 
  389     visualization_msgs::InteractiveMarkerControl control;
 
  390     std::stringstream ss;
 
  392     ss << hand << 
"_f" << finger << 
"_" << link;
 
  394     int_marker.name = ss.str() + 
"Marker";
 
  395     int_marker.header.frame_id = ss.str();
 
  398     int_marker.header.frame_id = 
frame_id;
 
  399     std::cout << ss.str() << std::endl;
 
  415     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  416     int_marker.controls.push_back(control);
 
  424     visualization_msgs::Marker 
marker;
 
  427     marker.type = visualization_msgs::Marker::CYLINDER;
 
  428     marker.action = visualization_msgs::Marker::ADD;
 
  429     marker.pose.position.x = 0;
 
  430     marker.pose.position.y = 0;
 
  431     marker.pose.position.z = 0.003;
 
  432     marker.pose.orientation.x = 0.0;
 
  433     marker.pose.orientation.y = 0.0;
 
  434     marker.pose.orientation.z = 0.0;
 
  435     marker.pose.orientation.w = 1.0;
 
  448     visualization_msgs::Marker 
marker;
 
  450     marker.type = visualization_msgs::Marker::CYLINDER;
 
  451     marker.action = visualization_msgs::Marker::ADD;
 
  452     marker.pose.position.x = 0.024;
 
  453     marker.pose.position.y = 0;
 
  454     marker.pose.position.z = 0;
 
  455     marker.pose.orientation.x = 0.0;
 
  456     marker.pose.orientation.y = 1.0;
 
  457     marker.pose.orientation.z = 0.0;
 
  458     marker.pose.orientation.w = 1.0;
 
  471     visualization_msgs::Marker 
marker;
 
  473     marker.type = visualization_msgs::Marker::CYLINDER;
 
  474     marker.action = visualization_msgs::Marker::ADD;
 
  475     marker.pose.position.x = 0.024;
 
  476     marker.pose.position.y = 0;
 
  477     marker.pose.position.z = 0;
 
  478     marker.pose.orientation.x = 0.0;
 
  479     marker.pose.orientation.y = 1.0;
 
  480     marker.pose.orientation.z = 0.0;
 
  481     marker.pose.orientation.w = 1.0;
 
  498     std::string ros_package_path = 
"";
 
  503     if ((fp = popen(
"echo $ROS_PACKAGE_PATH", 
"r")) == 
NULL) {
 
  504       std::cout << 
"popen error" << std::endl;
 
  506     while (fgets(buf, 
sizeof(buf), fp) != 
NULL) {
 
  507       ros_package_path += buf;
 
  511     if( path.find(
"file://", 0) == 0 ){
 
  515       size_t current = 0, found;
 
  516       while((found = ros_package_path.find_first_of(
":", current)) != std::string::npos){
 
  517         std::string search_path = std::string(ros_package_path, current, found - current);
 
  519         if(path.find(search_path, 0) == 0){
 
  520           path.erase(0, strlen(search_path.c_str()));
 
  525       std::string 
tmp[] = {
"", 
"jsk-ros-pkg", 
"jsk_model_tools"};
 
  526       std::set<std::string> package_blackset(
tmp, 
tmp + 
sizeof(
tmp) / 
sizeof(
tmp[0]));
 
  529       while((found = path.find_first_of(
"/", current)) != std::string::npos){
 
  530         std::string search_path = std::string(path, current, found - current);
 
  532         std::string package_path;
 
  535         if(package_blackset.find(search_path) != package_blackset.end()){
 
  540           return "package://" + search_path + path.erase(0, current-1);
 
  543       path = 
"file://" + path;
 
  550     std::string gazebo_model_path=
"";
 
  556     if ((fp = popen(
"echo $GAZEBO_MODEL_PATH", 
"r")) == 
NULL) {
 
  557       std::cout << 
"popen error" << std::endl;
 
  559     while (fgets(buf, 
sizeof(buf), fp) != 
NULL) {
 
  560       gazebo_model_path += buf;
 
  563     if( path.find(
"model://", 0) == 0 ){
 
  568       size_t current = 0, found;
 
  569       while((found = gazebo_model_path.find_first_of(
":", current)) != std::string::npos){
 
  571           std::string search_path = std::string(gazebo_model_path, current, found - current);
 
  573           recursive_directory_iterator iter = recursive_directory_iterator(search_path);
 
  574           recursive_directory_iterator 
end = recursive_directory_iterator();
 
  575           for (; iter != 
end; ++iter) {
 
  576             if (is_regular_file(*iter)) {
 
  577               int locate = iter->path().string().find( path, 0 );
 
  578               if( locate != std::string::npos){
 
  580                 return "file://" + iter->path().string();
 
  593     std::string path = rospath;
 
  594     if (path.find(
"package://") == 0){
 
  595       path.erase(0, strlen(
"package://"));
 
  596       size_t pos = path.find(
"/");
 
  597       if (
pos == std::string::npos){
 
  598         std::cout << 
"Could not parse package:// format" <<std::endl;
 
  601       std::string 
package = path.substr(0, pos);
 
  604       if (package_path.empty())
 
  606           std::cout <<  
"Package [" + 
package + "] does not exist" << std::endl;
 
  609       path = package_path + path;
 
  615     geometry_msgs::Pose 
p;
 
  622       p.position.x = 
p.position.y = 
p.position.z = 0.0;
 
  632       p.orientation.x = 
p.orientation.y = 
p.orientation.z = 0.0;
 
  633       p.orientation.w = 1.0;
 
  642       return (
double)((int)val);