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 #include <stdio.h>
00028 #include <vector>
00029 #include <math.h>
00030 #include <visualization_msgs/Marker.h>
00031 #include <visualization_msgs/MarkerArray.h>
00032 #include <numeric>
00033
00034 #include <pcl/ros/conversions.h>
00035 #include <pcl/point_cloud.h>
00036 #include <pcl/point_types.h>
00037 #include <interactive_markers/interactive_marker_server.h>
00038 #include <interactive_markers/menu_handler.h>
00039 #include <boost/lexical_cast.hpp>
00040 #include <boost/format.hpp>
00041 #include "std_msgs/String.h"
00042 #include <mtt/TargetListPC.h>
00043
00044
00045 using namespace visualization_msgs;
00046
00047
00048 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server;
00049 ros::NodeHandle* p_n;
00050 ros::Publisher coor_pub;
00051 visualization_msgs::Marker marker;
00052 ros::Publisher line_pub;
00053
00054 void processFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00055 {
00056 std::ostringstream mouse_point_ss;
00057 if( feedback->mouse_point_valid )
00058 {
00059
00060
00061
00062
00063 }
00064
00065 switch ( feedback->event_type )
00066 {
00067 case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
00068
00069
00070 mtt::TargetListPC message;
00071 message.header.stamp = ros::Time::now();
00072 message.header.frame_id = "/world";
00073
00074
00075 message.id.push_back(0);
00076
00077
00078 pcl::PointCloud<pcl::PointXYZ> pc_in;
00079 pcl::PointXYZ pt;
00080 pt.x = feedback->pose.position.x;
00081 pt.y = feedback->pose.position.y;
00082 pt.z = 0;
00083 pc_in.points.push_back(pt);
00084 pcl::toROSMsg(pc_in, message.position);
00085
00086
00087
00088 pcl::PointCloud<pcl::PointXYZ> pc_vel;
00089 pt.x = 0;
00090 pt.y = 0;
00091 pt.z = 0;
00092 pc_vel.points.push_back(pt);
00093 pcl::toROSMsg(pc_vel, message.velocity);
00094
00095
00096 pcl::PointCloud<pcl::PointXYZ> pc_obs;
00097 pt.x = feedback->pose.position.x +0;
00098 pt.y = feedback->pose.position.y -1;
00099 pt.z = 0;
00100 pc_obs.points.push_back(pt);
00101
00102 pt.x = feedback->pose.position.x +0;
00103 pt.y = feedback->pose.position.y +1;
00104 pt.z = 0;
00105 pc_obs.points.push_back(pt);
00106
00107 pt.x = feedback->pose.position.x +1;
00108 pt.y = feedback->pose.position.y +1;
00109 pt.z = 0;
00110 pc_obs.points.push_back(pt);
00111
00112 sensor_msgs::PointCloud2 pc_msg;
00113 pcl::toROSMsg(pc_obs, pc_msg);
00114
00115 message.obstacle_lines.push_back(pc_msg);
00116
00117
00118 coor_pub.publish(message);
00119
00120
00121
00122 geometry_msgs::Point p;
00123 marker.header.frame_id = "/world";
00124 marker.header.stamp = ros::Time::now();
00125 marker.ns = "lines";
00126 marker.id = 0;
00127 marker.action = visualization_msgs::Marker::ADD;
00128 marker.type = visualization_msgs::Marker::LINE_LIST;
00129 marker.scale.x = 0.015;
00130 marker.color.r = 0.7;
00131 marker.color.g = 0.1;
00132 marker.color.b = 0.1;
00133 marker.color.a = 1.0;
00134 marker.pose.position.x = feedback->pose.position.x;
00135 marker.pose.position.y = feedback->pose.position.y;
00136 marker.pose.position.z = 0;
00137
00138 p.x = 0;
00139 p.y = -1;
00140 p.z = 0;
00141 marker.points.push_back(p);
00142 p.x = 0;
00143 p.y = 1;
00144 p.z = 0;
00145 marker.points.push_back(p);
00146 marker.points.push_back(p);
00147 p.x = 1;
00148 p.y = 1;
00149 p.z = 0;
00150 marker.points.push_back(p);
00151
00152
00153 line_pub.publish(marker);
00154
00155 break;
00156 }
00157
00158 server->applyChanges();
00159 }
00160
00161
00162 Marker makeBox( InteractiveMarker &msg )
00163 {
00164 Marker marker;
00165
00166 marker.type = Marker::CUBE;
00167 marker.scale.x = msg.scale/7;
00168 marker.scale.y = msg.scale/7;
00169 marker.scale.z = msg.scale/7;
00170 marker.color.r = 0.7;
00171 marker.color.g = 0.1;
00172 marker.color.b = 0.1;
00173 marker.color.a = 0.8;
00174 return marker;
00175 }
00176
00177
00178 InteractiveMarkerControl& makeBoxControl( InteractiveMarker &msg )
00179 {
00180 InteractiveMarkerControl control;
00181 control.always_visible = true;
00182 control.markers.push_back( makeBox(msg) );
00183 msg.controls.push_back( control );
00184
00185 return msg.controls.back();
00186 }
00187
00188
00189 void make6DofMarker( bool fixed )
00190 {
00191 InteractiveMarker int_marker;
00192 int_marker.header.frame_id = "/world";
00193 int_marker.pose.position.x = 5;
00194 int_marker.pose.position.y = 4;
00195 int_marker.pose.position.z = 0;
00196 int_marker.scale = 0.4;
00197 int_marker.name = "Control obstacle";
00198 int_marker.description = "Control the final \nposition of the obstacle";
00199
00200
00201 makeBoxControl(int_marker);
00202 InteractiveMarkerControl control;
00203
00204 control.orientation.w = 1;
00205 control.orientation.x = 1;
00206 control.orientation.y = 0;
00207 control.orientation.z = 0;
00208 control.name = "move_x";
00209 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00210 int_marker.controls.push_back(control);
00211
00212 control.orientation.w = 1;
00213 control.orientation.x = 0;
00214 control.orientation.y = 0;
00215 control.orientation.z = 1;
00216 control.name = "move_y";
00217 control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00218 int_marker.controls.push_back(control);
00219
00220 server->insert(int_marker);
00221 server->setCallback(int_marker.name, &processFeedback);
00222 }
00223
00224
00225 int main(int argc, char **argv)
00226 {
00227 ros::init(argc, argv, "mtt_target_generator");
00228 ros::NodeHandle n("~");
00229 ros::Rate loop_rate(10);
00230 p_n=&n;
00231
00232 coor_pub = n.advertise<mtt::TargetListPC>("/mtt_targets", 1000);
00233
00234 line_pub = n.advertise<visualization_msgs::Marker>( "/line_markers", 1 );
00235
00236
00237 server.reset( new interactive_markers::InteractiveMarkerServer("mtt_target_generator/im","",false) );
00238 make6DofMarker( true );
00239 server->applyChanges();
00240
00241 while(ros::ok())
00242 {
00243 loop_rate.sleep();
00244 ros::spinOnce();
00245 }
00246
00247 server.reset();
00248 }