00001 #include <jsk_interactive_marker/interactive_marker_utils.h>
00002 #include <boost/filesystem/operations.hpp>
00003 #include <iostream>
00004 #include <stdlib.h>
00005 #include <ros/package.h>
00006 #include "urdf_parser/urdf_parser.h"
00007
00008 #include <kdl/frames_io.hpp>
00009 #include <tf_conversions/tf_kdl.h>
00010
00011 using namespace urdf;
00012 using namespace std;
00013 using namespace boost;
00014 using namespace boost::filesystem;
00015
00016
00017 namespace im_utils {
00018
00019
00020 geometry_msgs::Transform Pose2Transform( const geometry_msgs::Pose pose_msg){
00021 geometry_msgs::Transform tf_msg;
00022 tf_msg.translation.x = pose_msg.position.x;
00023 tf_msg.translation.y = pose_msg.position.y;
00024 tf_msg.translation.z = pose_msg.position.z;
00025 tf_msg.rotation = pose_msg.orientation;
00026 return tf_msg;
00027 }
00028
00029 geometry_msgs::Pose Transform2Pose( const geometry_msgs::Transform tf_msg){
00030 geometry_msgs::Pose pose_msg;
00031 pose_msg.position.x = tf_msg.translation.x;
00032 pose_msg.position.y = tf_msg.translation.y;
00033 pose_msg.position.z = tf_msg.translation.z;
00034 pose_msg.orientation = tf_msg.rotation;
00035 return pose_msg;
00036 }
00037
00038 geometry_msgs::Pose UrdfPose2Pose( const urdf::Pose pose){
00039 geometry_msgs::Pose p_msg;
00040 double x, y, z, w;
00041 pose.rotation.getQuaternion(x,y,z,w);
00042 p_msg.orientation.x = x;
00043 p_msg.orientation.y = y;
00044 p_msg.orientation.z = z;
00045 p_msg.orientation.w = w;
00046
00047 p_msg.position.x = pose.position.x;
00048 p_msg.position.y = pose.position.y;
00049 p_msg.position.z = pose.position.z;
00050
00051 return p_msg;
00052 }
00053
00054
00055 visualization_msgs::InteractiveMarkerControl makeCylinderMarkerControl(const geometry_msgs::PoseStamped &stamped, double length, double radius, const std_msgs::ColorRGBA &color, bool use_color){
00056 visualization_msgs::Marker cylinderMarker;
00057
00058 if (use_color) cylinderMarker.color = color;
00059 cylinderMarker.type = visualization_msgs::Marker::CYLINDER;
00060 cylinderMarker.scale.x = radius * 2;
00061 cylinderMarker.scale.y = radius * 2;
00062 cylinderMarker.scale.z = length;
00063 cylinderMarker.pose = stamped.pose;
00064
00065 visualization_msgs::InteractiveMarkerControl control;
00066 control.markers.push_back( cylinderMarker );
00067 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00068 control.always_visible = true;
00069
00070 return control;
00071 }
00072
00073 visualization_msgs::InteractiveMarkerControl makeBoxMarkerControl(const geometry_msgs::PoseStamped &stamped, Vector3 dim, const std_msgs::ColorRGBA &color, bool use_color){
00074 visualization_msgs::Marker boxMarker;
00075
00076 fprintf(stderr, "urdfModelMarker = %f %f %f\n", dim.x, dim.y, dim.z);
00077 if (use_color) boxMarker.color = color;
00078 boxMarker.type = visualization_msgs::Marker::CUBE;
00079 boxMarker.scale.x = dim.x;
00080 boxMarker.scale.y = dim.y;
00081 boxMarker.scale.z = dim.z;
00082 boxMarker.pose = stamped.pose;
00083
00084 visualization_msgs::InteractiveMarkerControl control;
00085 control.markers.push_back( boxMarker );
00086 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00087 control.always_visible = true;
00088
00089 return control;
00090 }
00091
00092 visualization_msgs::InteractiveMarkerControl makeSphereMarkerControl(const geometry_msgs::PoseStamped &stamped, double rad, const std_msgs::ColorRGBA &color, bool use_color){
00093 visualization_msgs::Marker sphereMarker;
00094
00095 if (use_color) sphereMarker.color = color;
00096 sphereMarker.type = visualization_msgs::Marker::SPHERE;
00097 sphereMarker.scale.x = rad * 2;
00098 sphereMarker.scale.y = rad * 2;
00099 sphereMarker.scale.z = rad * 2;
00100 sphereMarker.pose = stamped.pose;
00101
00102 visualization_msgs::InteractiveMarkerControl control;
00103 control.markers.push_back( sphereMarker );
00104 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00105 control.always_visible = true;
00106
00107 return control;
00108 }
00109
00110
00111
00112 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){
00113 visualization_msgs::Marker meshMarker;
00114
00115 if (use_color) meshMarker.color = color;
00116 meshMarker.mesh_resource = mesh_resource;
00117 meshMarker.mesh_use_embedded_materials = !use_color;
00118 meshMarker.type = visualization_msgs::Marker::MESH_RESOURCE;
00119
00120 meshMarker.scale = scale;
00121 meshMarker.pose = stamped.pose;
00122 visualization_msgs::InteractiveMarkerControl control;
00123 control.markers.push_back( meshMarker );
00124 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00125 control.always_visible = true;
00126
00127 return control;
00128 }
00129
00130 visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource, const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale)
00131 {
00132 std_msgs::ColorRGBA color;
00133 color.r = 0;
00134 color.g = 0;
00135 color.b = 0;
00136 color.a = 0;
00137 return makeMeshMarkerControl(mesh_resource, stamped, scale, color, false);
00138 }
00139
00140 visualization_msgs::InteractiveMarkerControl makeMeshMarkerControl(const std::string &mesh_resource,
00141 const geometry_msgs::PoseStamped &stamped, geometry_msgs::Vector3 scale, const std_msgs::ColorRGBA &color)
00142 {
00143 return makeMeshMarkerControl(mesh_resource, stamped, scale, color, true);
00144 }
00145
00146 void addMeshLinksControl(visualization_msgs::InteractiveMarker &im, boost::shared_ptr<const Link> link, KDL::Frame previous_frame, bool use_color, std_msgs::ColorRGBA color, double scale){
00147 addMeshLinksControl(im, link, previous_frame, use_color, color, scale, true);
00148 }
00149
00150 void addMeshLinksControl(visualization_msgs::InteractiveMarker &im, boost::shared_ptr<const Link> link, KDL::Frame previous_frame, bool use_color, std_msgs::ColorRGBA color, double scale, bool root){
00151 if(!root && link->parent_joint){
00152 KDL::Frame parent_to_joint_frame;
00153 geometry_msgs::Pose parent_to_joint_pose = UrdfPose2Pose(link->parent_joint->parent_to_joint_origin_transform);
00154 tf::poseMsgToKDL(parent_to_joint_pose, parent_to_joint_frame);
00155 previous_frame = previous_frame * parent_to_joint_frame;
00156 }
00157
00158
00159
00160
00161
00162
00163 geometry_msgs::PoseStamped ps;
00164
00165 std::vector<boost ::shared_ptr<Visual> > visual_array;
00166 if(link->visual_array.size() != 0){
00167 visual_array = link->visual_array;
00168 }else if(link->visual.get() != NULL){
00169 visual_array.push_back(link->visual);
00170 }
00171 for(int i=0; i<visual_array.size(); i++){
00172 boost::shared_ptr<Visual> link_visual = visual_array[i];
00173 if(link_visual.get() != NULL && link_visual->geometry.get() != NULL){
00174 visualization_msgs::InteractiveMarkerControl meshControl;
00175 if(link_visual->geometry->type == Geometry::MESH){
00176 boost::shared_ptr<const Mesh> mesh = boost::static_pointer_cast<const Mesh>(link_visual->geometry);
00177 string model_mesh_ = mesh->filename;
00178 model_mesh_ = getRosPathFromModelPath(model_mesh_);
00179
00180
00181 KDL::Frame pose_frame, origin_frame;
00182
00183 tf::poseMsgToKDL(UrdfPose2Pose(link_visual->origin), origin_frame);
00184 pose_frame = previous_frame * origin_frame;
00185 geometry_msgs::Pose pose;
00186 tf::poseKDLToMsg(pose_frame, pose);
00187 ps.pose = pose;
00188
00189 cout << "mesh_file:" << model_mesh_ << endl;
00190
00191 geometry_msgs::Vector3 mesh_scale;
00192 mesh_scale.x = mesh->scale.x * scale;
00193 mesh_scale.y = mesh->scale.y * scale;
00194 mesh_scale.z = mesh->scale.z * scale;
00195 if(use_color){
00196 meshControl = makeMeshMarkerControl(model_mesh_, ps, mesh_scale, color);
00197 }else{
00198 meshControl = makeMeshMarkerControl(model_mesh_, ps, mesh_scale);
00199 }
00200 }else if(link_visual->geometry->type == Geometry::CYLINDER){
00201 boost::shared_ptr<const Cylinder> cylinder = boost::static_pointer_cast<const Cylinder>(link_visual->geometry);
00202 std::cout << "cylinder " << link->name;
00203 ps.pose = UrdfPose2Pose(link_visual->origin);
00204 double length = cylinder->length;
00205 double radius = cylinder->radius;
00206 std::cout << ", length = " << length << ", radius " << radius << std::endl;
00207 if(use_color){
00208 meshControl = makeCylinderMarkerControl(ps, length, radius, color, true);
00209 }else{
00210 meshControl = makeCylinderMarkerControl(ps, length, radius, color, true);
00211 }
00212 }else if(link_visual->geometry->type == Geometry::BOX){
00213 boost::shared_ptr<const Box> box = boost::static_pointer_cast<const Box>(link_visual->geometry);
00214 std::cout << "box " << link->name;
00215 ps.pose = UrdfPose2Pose(link_visual->origin);
00216 Vector3 dim = box->dim;
00217 std::cout << ", dim = " << dim.x << ", " << dim.y << ", " << dim.z << std::endl;
00218 if(use_color){
00219 meshControl = makeBoxMarkerControl(ps, dim, color, true);
00220 }else{
00221 meshControl = makeBoxMarkerControl(ps, dim, color, true);
00222 }
00223 }else if(link_visual->geometry->type == Geometry::SPHERE){
00224 boost::shared_ptr<const Sphere> sphere = boost::static_pointer_cast<const Sphere>(link_visual->geometry);
00225 ps.pose = UrdfPose2Pose(link_visual->origin);
00226 double rad = sphere->radius;
00227 if(use_color){
00228 meshControl = makeSphereMarkerControl(ps, rad, color, true);
00229 }else{
00230 meshControl = makeSphereMarkerControl(ps, rad, color, true);
00231 }
00232 }
00233 im.controls.push_back( meshControl );
00234
00235 }
00236 }
00237 for (std::vector<boost::shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++){
00238 addMeshLinksControl(im, *child, previous_frame, use_color, color, scale, false);
00239 }
00240 }
00241
00242 boost::shared_ptr<ModelInterface> getModelInterface(std::string model_file){
00243 boost::shared_ptr<ModelInterface> model;
00244 model_file = getFilePathFromRosPath(model_file);
00245 model_file = getFullPathFromModelPath(model_file);
00246 std::string xml_string;
00247 std::fstream xml_file(model_file.c_str(), std::fstream::in);
00248 while ( xml_file.good() )
00249 {
00250 std::string line;
00251 std::getline( xml_file, line);
00252 xml_string += (line + "\n");
00253 }
00254 xml_file.close();
00255
00256 std::cout << "model_file:" << model_file << std::endl;
00257 model = parseURDF(xml_string);
00258 if (!model){
00259 std::cerr << "ERROR: Model Parsing the xml failed" << std::endl;
00260 }
00261 return model;
00262 }
00263
00264
00265 visualization_msgs::InteractiveMarker makeLinksMarker(boost::shared_ptr<const Link> link, bool use_color, std_msgs::ColorRGBA color, geometry_msgs::PoseStamped marker_ps, geometry_msgs::Pose origin_pose)
00266 {
00267 visualization_msgs::InteractiveMarker int_marker;
00268 int_marker.header = marker_ps.header;
00269 int_marker.pose = marker_ps.pose;
00270
00271 int_marker.name = "sample";
00272 int_marker.scale = 1.0;
00273
00274 KDL::Frame origin_frame;
00275 tf::poseMsgToKDL(origin_pose, origin_frame);
00276 addMeshLinksControl(int_marker, link, origin_frame, use_color, color, 1.0);
00277 return int_marker;
00278
00279 }
00280
00281
00282
00283 visualization_msgs::InteractiveMarker makeFingerControlMarker(const char *name, geometry_msgs::PoseStamped ps){
00284 visualization_msgs::InteractiveMarker int_marker;
00285 int_marker.name = name;
00286 int_marker.header = ps.header;
00287 int_marker.pose = ps.pose;
00288 int_marker.scale = 0.5;
00289
00290 visualization_msgs::InteractiveMarkerControl control;
00291
00292
00293 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00294 control.orientation.w = 1;
00295 control.orientation.x = 0;
00296 control.orientation.y = 0;
00297 control.orientation.z = 1;
00298
00299 int_marker.controls.push_back(control);
00300
00301 return int_marker;
00302
00303 }
00304
00305
00306
00307
00308
00309
00310
00311
00312
00313
00314
00315
00316
00317
00318
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331
00332
00333
00334
00335
00336
00337
00338
00339
00340
00341
00342
00343
00344
00345
00346
00347
00348
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358
00359
00360
00361
00362
00363
00364
00365
00366
00367 visualization_msgs::InteractiveMarker makeSandiaHandInteractiveMarker(geometry_msgs::PoseStamped ps, std::string hand, int finger, int link){
00368 visualization_msgs::InteractiveMarker int_marker;
00369 int_marker.header = ps.header;
00370 int_marker.pose = ps.pose;
00371
00372
00373 visualization_msgs::InteractiveMarkerControl control;
00374 std::stringstream ss;
00375
00376 ss << hand << "_f" << finger << "_" << link;
00377
00378 int_marker.name = ss.str() + "Marker";
00379 int_marker.header.frame_id = ss.str();
00380
00381 std::string frame_id = "utorso";
00382 int_marker.header.frame_id = frame_id;
00383 std::cout << ss.str() << std::endl;
00384
00385
00386 switch(link){
00387 case 0:
00388 control.markers.push_back(makeSandiaFinger0Marker(frame_id));
00389 break;
00390 case 1:
00391 control.markers.push_back(makeSandiaFinger1Marker(frame_id));
00392 break;
00393 case 2:
00394 control.markers.push_back(makeSandiaFinger2Marker(frame_id));
00395 break;
00396 default:
00397 break;
00398 }
00399 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00400 int_marker.controls.push_back(control);
00401
00402 return int_marker;
00403 }
00404
00405
00406
00407 visualization_msgs::Marker makeSandiaFinger0Marker(std::string frame_id){
00408 visualization_msgs::Marker marker;
00409 marker.header.frame_id = frame_id;
00410
00411 marker.type = visualization_msgs::Marker::CYLINDER;
00412 marker.action = visualization_msgs::Marker::ADD;
00413 marker.pose.position.x = 0;
00414 marker.pose.position.y = 0;
00415 marker.pose.position.z = 0.003;
00416 marker.pose.orientation.x = 0.0;
00417 marker.pose.orientation.y = 0.0;
00418 marker.pose.orientation.z = 0.0;
00419 marker.pose.orientation.w = 1.0;
00420 marker.scale.x = 0.03;
00421 marker.scale.y = 0.03;
00422 marker.scale.z = 0.023;
00423 marker.color.a = 1.0;
00424 marker.color.r = 0.0;
00425 marker.color.g = 1.0;
00426 marker.color.b = 0.0;
00427
00428 return marker;
00429 }
00430
00431 visualization_msgs::Marker makeSandiaFinger1Marker(std::string frame_id){
00432 visualization_msgs::Marker marker;
00433 marker.header.frame_id = frame_id;
00434 marker.type = visualization_msgs::Marker::CYLINDER;
00435 marker.action = visualization_msgs::Marker::ADD;
00436 marker.pose.position.x = 0.024;
00437 marker.pose.position.y = 0;
00438 marker.pose.position.z = 0;
00439 marker.pose.orientation.x = 0.0;
00440 marker.pose.orientation.y = 1.0;
00441 marker.pose.orientation.z = 0.0;
00442 marker.pose.orientation.w = 1.0;
00443 marker.scale.x = 0.02;
00444 marker.scale.y = 0.02;
00445 marker.scale.z = 0.067;
00446 marker.color.a = 1.0;
00447 marker.color.r = 0.0;
00448 marker.color.g = 1.0;
00449 marker.color.b = 0.0;
00450
00451 return marker;
00452 }
00453
00454 visualization_msgs::Marker makeSandiaFinger2Marker(std::string frame_id){
00455 visualization_msgs::Marker marker;
00456 marker.header.frame_id = frame_id;
00457 marker.type = visualization_msgs::Marker::CYLINDER;
00458 marker.action = visualization_msgs::Marker::ADD;
00459 marker.pose.position.x = 0.024;
00460 marker.pose.position.y = 0;
00461 marker.pose.position.z = 0;
00462 marker.pose.orientation.x = 0.0;
00463 marker.pose.orientation.y = 1.0;
00464 marker.pose.orientation.z = 0.0;
00465 marker.pose.orientation.w = 1.0;
00466 marker.scale.x = 0.018;
00467 marker.scale.y = 0.018;
00468 marker.scale.z = 0.057;
00469 marker.color.a = 1.0;
00470 marker.color.r = 0.0;
00471 marker.color.g = 1.0;
00472 marker.color.b = 0.0;
00473
00474 return marker;
00475 }
00476
00477 std::string getRosPathFromModelPath(std::string path){
00478 return getRosPathFromFullPath(getFullPathFromModelPath(path));
00479 }
00480
00481 std::string getRosPathFromFullPath(std::string path){
00482 std::string ros_package_path = "";
00483 FILE* fp;
00484 char buf[1000000];
00485
00486
00487 if ((fp = popen("echo $ROS_PACKAGE_PATH", "r")) == NULL) {
00488 std::cout << "popen error" << std::endl;
00489 }
00490 while (fgets(buf, sizeof(buf), fp) != NULL) {
00491 ros_package_path += buf;
00492 }
00493 pclose(fp);
00494
00495 if( path.find("file://", 0) == 0 ){
00496 path.erase(0,7);
00497
00498
00499 size_t current = 0, found;
00500 while((found = ros_package_path.find_first_of(":", current)) != std::string::npos){
00501 std::string search_path = std::string(ros_package_path, current, found - current);
00502 current = found + 1;
00503 if(path.find(search_path, 0) == 0){
00504 path.erase(0, strlen(search_path.c_str()));
00505 break;
00506 }
00507 }
00508
00509 std::string tmp[] = {"", "jsk-ros-pkg", "jsk_model_tools"};
00510 std::set<std::string> package_blackset(tmp, tmp + sizeof(tmp) / sizeof(tmp[0]));
00511
00512 current = 0;
00513 while((found = path.find_first_of("/", current)) != std::string::npos){
00514 std::string search_path = std::string(path, current, found - current);
00515 current = found + 1;
00516 std::string package_path;
00517
00518
00519 if(package_blackset.find(search_path) != package_blackset.end()){
00520 continue;
00521 }
00522
00523 if( search_path != "" && ros::package::getPath(search_path) != ""){
00524 return "package://" + search_path + path.erase(0, current-1);
00525 }
00526 }
00527 path = "file://" + path;
00528 }
00529
00530 return path;
00531 }
00532
00533 std::string getFullPathFromModelPath(std::string path){
00534 std::string gazebo_model_path="";
00535
00536 FILE* fp;
00537 char buf[1000000];
00538
00539
00540 if ((fp = popen("echo $GAZEBO_MODEL_PATH", "r")) == NULL) {
00541 std::cout << "popen error" << std::endl;
00542 }
00543 while (fgets(buf, sizeof(buf), fp) != NULL) {
00544 gazebo_model_path += buf;
00545 }
00546 pclose(fp);
00547 if( path.find("model://", 0) == 0 ){
00548 path.erase(0,8);
00549
00550
00551
00552 size_t current = 0, found;
00553 while((found = gazebo_model_path.find_first_of(":", current)) != std::string::npos){
00554 try{
00555 std::string search_path = std::string(gazebo_model_path, current, found - current);
00556 current = found + 1;
00557 recursive_directory_iterator iter = recursive_directory_iterator(search_path);
00558 recursive_directory_iterator end = recursive_directory_iterator();
00559 for (; iter != end; ++iter) {
00560 if (is_regular_file(*iter)) {
00561 int locate = iter->path().string().find( path, 0 );
00562 if( locate != std::string::npos){
00563
00564 return "file://" + iter->path().string();
00565 }
00566 }
00567 }
00568 }catch(...){
00569 }
00570 }
00571 }
00572 return path;
00573 }
00574
00575
00576 std::string getFilePathFromRosPath( std::string rospath){
00577 std::string path = rospath;
00578 if (path.find("package://") == 0){
00579 path.erase(0, strlen("package://"));
00580 size_t pos = path.find("/");
00581 if (pos == std::string::npos){
00582 std::cout << "Could not parse package:// format" <<std::endl;
00583 return "";
00584 }
00585 std::string package = path.substr(0, pos);
00586 path.erase(0, pos);
00587 std::string package_path = ros::package::getPath(package);
00588 if (package_path.empty())
00589 {
00590 std::cout << "Package [" + package + "] does not exist" << std::endl;
00591 }
00592
00593 path = package_path + path;
00594 }
00595 return path;
00596 }
00597
00598 geometry_msgs::Pose getPose( XmlRpc::XmlRpcValue val){
00599 geometry_msgs::Pose p;
00600 if(val.hasMember("position")){
00601 XmlRpc::XmlRpcValue pos = val["position"];
00602 p.position.x = getXmlValue(pos["x"]);
00603 p.position.y = getXmlValue(pos["y"]);
00604 p.position.z = getXmlValue(pos["z"]);
00605 }else{
00606 p.position.x = p.position.y = p.position.z = 0.0;
00607 }
00608
00609 if(val.hasMember("orientation")){
00610 XmlRpc::XmlRpcValue ori = val["orientation"];
00611 p.orientation.x = getXmlValue(ori["x"]);
00612 p.orientation.y = getXmlValue(ori["y"]);
00613 p.orientation.z = getXmlValue(ori["z"]);
00614 p.orientation.w = getXmlValue(ori["w"]);
00615 }else{
00616 p.orientation.x = p.orientation.y = p.orientation.z = 0.0;
00617 p.orientation.w = 1.0;
00618 }
00619
00620 return p;
00621 }
00622
00623 double getXmlValue( XmlRpc::XmlRpcValue val ){
00624 switch(val.getType()){
00625 case XmlRpc::XmlRpcValue::TypeInt:
00626 return (double)((int)val);
00627 case XmlRpc::XmlRpcValue::TypeDouble:
00628 return (double)val;
00629 default:
00630 return 0;
00631 }
00632 }
00633
00634 }
00635
00636