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
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include <ros/ros.h>
00038 #include "jsk_pcl_ros/geo_util.h"
00039 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00040 #include <interactive_markers/interactive_marker_server.h>
00041 #include <visualization_msgs/Marker.h>
00042 #include <visualization_msgs/MarkerArray.h>
00043 #include <geometry_msgs/PointStamped.h>
00044
00045 using namespace jsk_pcl_ros;
00046
00047 Cube cube(Eigen::Vector3f(1, 0, 0),
00048 Eigen::Quaternionf(0.108755, 0.088921, 0.108755, 0.984092),
00049 Eigen::Vector3f(0.3, 0.3, 0.3));
00050
00051 ros::Publisher pub_nearest_point;
00052 void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
00053 {
00054 Eigen::Vector3f p(feedback->pose.position.x, feedback->pose.position.y, feedback->pose.position.z);
00055 double distance;
00056 Eigen::Vector3f q = cube.nearestPoint(p, distance);
00057 ROS_INFO("distance: %f", distance);
00058 geometry_msgs::PointStamped ps;
00059 ps.header = feedback->header;
00060 ps.point.x = q[0];
00061 ps.point.y = q[1];
00062 ps.point.z = q[2];
00063 pub_nearest_point.publish(ps);
00064 }
00065
00066 int main(int argc, char** argv)
00067 {
00068 ros::init(argc, argv, "cube_nearest_point");
00069 ros::NodeHandle nh("~");
00070 pub_nearest_point = nh.advertise<geometry_msgs::PointStamped>("nearest_point", 1);
00071 interactive_markers::InteractiveMarkerServer server("sample_cube_nearest_point");
00072
00073 visualization_msgs::InteractiveMarker int_marker;
00074 int_marker.header.frame_id = "world";
00075 int_marker.name = "marker";
00076 int_marker.pose.orientation.w = 1.0;
00077 int_marker.pose.position.x = -2.0;
00078 visualization_msgs::Marker object_marker;
00079 object_marker.type = visualization_msgs::Marker::SPHERE;
00080 object_marker.scale.x = 0.1;
00081 object_marker.scale.y = 0.1;
00082 object_marker.scale.z = 0.1;
00083 object_marker.color.r = 1.0;
00084 object_marker.color.g = 1.0;
00085 object_marker.color.b = 1.0;
00086 object_marker.color.a = 1.0;
00087 visualization_msgs::InteractiveMarkerControl object_marker_control;
00088 object_marker_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00089 object_marker_control.always_visible = true;
00090 object_marker_control.markers.push_back(object_marker);
00091 int_marker.controls.push_back(object_marker_control);
00092 visualization_msgs::InteractiveMarkerControl control;
00093 control.orientation.w = 1;
00094 control.orientation.x = 1;
00095 control.orientation.y = 0;
00096 control.orientation.z = 0;
00097
00098 control.name = "move_x";
00099 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00100 int_marker.controls.push_back(control);
00101
00102 control.orientation.w = 1;
00103 control.orientation.x = 0;
00104 control.orientation.y = 1;
00105 control.orientation.z = 0;
00106 control.name = "move_z";
00107 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00108 int_marker.controls.push_back(control);
00109
00110 control.orientation.w = 1;
00111 control.orientation.x = 0;
00112 control.orientation.y = 0;
00113 control.orientation.z = 1;
00114 control.name = "move_y";
00115 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00116 int_marker.controls.push_back(control);
00117 server.insert(int_marker, &processFeedbackCB);
00118 server.applyChanges();
00119
00120 ros::Publisher pub_box_array = nh.advertise<jsk_recognition_msgs::BoundingBoxArray>("bbox_array", 1, true);
00121 jsk_recognition_msgs::BoundingBox box = cube.toROSMsg();
00122 box.header.frame_id = "world";
00123 box.header.stamp = ros::Time::now();
00124 jsk_recognition_msgs::BoundingBoxArray box_array;
00125 box_array.boxes.push_back(box);
00126 box_array.header = box.header;
00127 pub_box_array.publish(box_array);
00128 ros::spin();
00129 }