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 #include <ros/ros.h>
00034
00035 #include <fast_plane_detection/Plane.h>
00036 #include <fast_plane_detection/PlaneInRegion.h>
00037
00038 #include <fast_plane_detector/utils.h>
00039
00040 #include <geometry_msgs/Vector3Stamped.h>
00041 #include <visualization_msgs/Marker.h>
00042
00043 int main(int argc, char **argv)
00044 {
00048 ros::init(argc, argv, "detect_plane_in_region");
00049 if (argc != 4)
00050 {
00051 ROS_INFO("usage: detect_plane_in_region X Y Z");
00052 return 1;
00053 }
00054
00055
00056 ros::NodeHandle n;
00057
00058 ros::ServiceClient client
00059 = n.serviceClient<fast_plane_detection::PlaneInRegion>("fast_plane_detection");
00060
00061
00063 ros::Publisher plane_marker_pub_;
00064
00065 plane_marker_pub_
00066 = n.advertise<visualization_msgs::Marker>("region_plane_markers", 1);
00067
00068 fast_plane_detection::PlaneInRegion srv;
00069 geometry_msgs::Vector3Stamped point;
00070 point.header.frame_id = "narrow_stereo_optical_frame";
00071 point.header.stamp = ros::Time::now();
00072 point.vector.x = atoll(argv[1]);
00073 point.vector.y = atoll(argv[2]);
00074 point.vector.z = atoll(argv[3]);
00075
00076 srv.request.point = point;
00077 srv.request.width = 10;
00078 srv.request.height = 50;
00079
00080 int marker_id = 345;
00081
00082
00083
00084 if (client.call(srv))
00085 {
00086 ROS_INFO("Service call returned successfully");
00087 ROS_INFO("srv.response.plane.top_left %f %f %f",
00088 srv.response.plane.top_left.x,
00089 srv.response.plane.top_left.y,
00090 srv.response.plane.top_left.z);
00091
00092
00093
00094 visualization_msgs::Marker delete_marker;
00095 delete_marker.header.stamp = ros::Time::now();
00096 delete_marker.header.frame_id = point.header.frame_id;
00097 delete_marker.id = marker_id;
00098 delete_marker.action = visualization_msgs::Marker::DELETE;
00099 delete_marker.ns = "tabletop_node";
00100 plane_marker_pub_.publish(delete_marker);
00101
00102
00103
00104 visualization_msgs::Marker planeMarker
00105 = fast_plane_detection::getPlaneMarker( srv.response.plane.top_left,
00106 srv.response.plane.top_right,
00107 srv.response.plane.bottom_left,
00108 srv.response.plane.bottom_right);
00109 planeMarker.header.frame_id = point.header.frame_id;
00110 planeMarker.header.stamp = ros::Time::now();
00111 planeMarker.pose = srv.response.plane.pose.pose;
00112 planeMarker.ns = "tabletop_node";
00113 planeMarker.id = marker_id;
00114 plane_marker_pub_.publish(planeMarker);
00115
00116
00117 } else {
00118 ROS_ERROR("Failed to call service fast_plane_detection");
00119 return 1;
00120 }
00121
00122 return 0;
00123 }