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 #include <string>
00036
00037 #include <ros/ros.h>
00038
00039 #include <visualization_msgs/Marker.h>
00040
00041 #include <household_objects_database_msgs/GetModelMesh.h>
00042
00043 visualization_msgs::Marker getFitMarker(const arm_navigation_msgs::Shape &mesh)
00044 {
00045 visualization_msgs::Marker marker;
00046 marker.action = visualization_msgs::Marker::ADD;
00047 marker.lifetime = ros::Duration();
00048 marker.type = visualization_msgs::Marker::POINTS;
00049 marker.color.a = 1.0;
00050 marker.color.r = 1.0;
00051 marker.color.g = 0.0;
00052 marker.color.b = 0.0;
00053 marker.scale.x = 0.003;
00054 marker.scale.y = 0.003;
00055 marker.points.insert(marker.points.begin(), mesh.vertices.begin(), mesh.vertices.end());
00056
00057 for (int i=0; i<40; i++)
00058 {
00059 geometry_msgs::Point p;
00060 p.x = 0.0005 * i;
00061 p.y = p.z = 0.0;
00062 marker.points.push_back(p);
00063 }
00064 return marker;
00065 }
00066
00067 int main(int argc, char **argv)
00068 {
00069 if (argc < 2)
00070 {
00071 ROS_ERROR("Usage: publish_database_object model_id");
00072 exit(0);
00073 }
00074
00075
00076 ros::Publisher marker_pub_;
00077 ros::ServiceClient get_model_mesh_srv_;
00078 ros::init(argc, argv, "publish_database_mesh");
00079 ros::NodeHandle nh_("");
00080
00081
00082 marker_pub_ = nh_.advertise<visualization_msgs::Marker>(nh_.resolveName("database_object"), 10);
00083
00084 ros::Duration(1.0).sleep();
00085
00086
00087 std::string get_model_mesh_srv_name = "/objects_database_node/get_model_mesh";
00088 while ( !ros::service::waitForService(get_model_mesh_srv_name, ros::Duration(2.0)) && nh_.ok() )
00089 {
00090 ROS_INFO("Waiting for %s service to come up", get_model_mesh_srv_name.c_str());
00091 }
00092 if (!nh_.ok()) exit(0);
00093 get_model_mesh_srv_ = nh_.serviceClient<household_objects_database_msgs::GetModelMesh>
00094 (get_model_mesh_srv_name, true);
00095
00096 int model_id = atoi(argv[1]);
00097 ROS_INFO("Publishing mesh for model %d", model_id);
00098
00099
00100 household_objects_database_msgs::GetModelMesh get_mesh;
00101 get_mesh.request.model_id = model_id;
00102 if ( !get_model_mesh_srv_.call(get_mesh) ||
00103 get_mesh.response.return_code.code != get_mesh.response.return_code.SUCCESS )
00104 {
00105 ROS_ERROR("Failed to call database get mesh service for marker display");
00106 exit(0);
00107 }
00108
00109 visualization_msgs::Marker fitMarker = getFitMarker(get_mesh.response.mesh);
00110
00111 fitMarker.header.frame_id = "foo_frame";
00112 fitMarker.header.stamp = ros::Time::now();
00113
00114 fitMarker.pose.orientation.w = 1;
00115 fitMarker.ns = "publish_database_object";
00116 fitMarker.id = 0;
00117 marker_pub_.publish(fitMarker);
00118
00119 ROS_INFO("Marker published");
00120
00121 ros::Duration(1.0).sleep();
00122 }