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 #include <ros/ros.h>
00033 #include <stdlib.h>
00034
00035 #include <interactive_markers/interactive_marker_server.h>
00036 #include <interactive_markers/tools.h>
00037
00038 #include <LinearMath/btVector3.h>
00039 #include <LinearMath/btAabbUtil2.h>
00040
00041 namespace vm = visualization_msgs;
00042
00043 class PointCouldSelector
00044 {
00045 public:
00046 PointCouldSelector( boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server,
00047 std::vector<btVector3>& points ) :
00048 server_( server ),
00049 min_sel_( -1, -1, -1 ),
00050 max_sel_( 1, 1, 1 ),
00051 points_( points )
00052 {
00053 updateBox( );
00054 updatePointClouds();
00055
00056 makeSizeHandles();
00057 }
00058
00059 void processAxisFeedback(
00060 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00061 {
00062 ROS_INFO_STREAM( feedback->marker_name << " is now at "
00063 << feedback->pose.position.x << ", " << feedback->pose.position.y
00064 << ", " << feedback->pose.position.z );
00065
00066 if ( feedback->marker_name == "min_x" ) min_sel_.setX( feedback->pose.position.x );
00067 if ( feedback->marker_name == "max_x" ) max_sel_.setX( feedback->pose.position.x );
00068 if ( feedback->marker_name == "min_y" ) min_sel_.setY( feedback->pose.position.y );
00069 if ( feedback->marker_name == "max_y" ) max_sel_.setY( feedback->pose.position.y );
00070 if ( feedback->marker_name == "min_z" ) min_sel_.setZ( feedback->pose.position.z );
00071 if ( feedback->marker_name == "max_z" ) max_sel_.setZ( feedback->pose.position.z );
00072
00073 updateBox( );
00074 updateSizeHandles();
00075
00076 if ( feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP )
00077 {
00078 updatePointClouds();
00079 }
00080
00081 server_->applyChanges();
00082 }
00083
00084 vm::Marker makeBox( vm::InteractiveMarker &msg,
00085 btVector3 min_bound, btVector3 max_bound )
00086 {
00087 vm::Marker marker;
00088
00089 marker.type = vm::Marker::CUBE;
00090 marker.scale.x = max_bound.x() - min_bound.x();
00091 marker.scale.y = max_bound.y() - min_bound.y();
00092 marker.scale.z = max_bound.z() - min_bound.z();
00093 marker.pose.position.x = 0.5 * ( max_bound.x() + min_bound.x() );
00094 marker.pose.position.y = 0.5 * ( max_bound.y() + min_bound.y() );
00095 marker.pose.position.z = 0.5 * ( max_bound.z() + min_bound.z() );
00096 marker.color.r = 0.5;
00097 marker.color.g = 0.5;
00098 marker.color.b = 0.5;
00099 marker.color.a = 0.5;
00100
00101 return marker;
00102 }
00103
00104 void updateBox( )
00105 {
00106 vm::InteractiveMarker msg;
00107 msg.header.frame_id = "/base_link";
00108
00109 vm::InteractiveMarkerControl control;
00110 control.always_visible = false;
00111 control.markers.push_back( makeBox(msg, min_sel_, max_sel_) );
00112 msg.controls.push_back( control );
00113
00114 server_->insert( msg );
00115 }
00116
00117 void updatePointCloud( std::string name, std_msgs::ColorRGBA color, std::vector<btVector3> &points )
00118 {
00119
00120 vm::InteractiveMarker int_marker;
00121 int_marker.header.frame_id = "/base_link";
00122 int_marker.name = name;
00123
00124
00125 vm::Marker points_marker;
00126 points_marker.type = vm::Marker::SPHERE_LIST;
00127 points_marker.scale.x = 0.05;
00128 points_marker.scale.y = 0.05;
00129 points_marker.scale.z = 0.05;
00130 points_marker.color = color;
00131
00132 for ( unsigned i=0; i<points.size(); i++ )
00133 {
00134 geometry_msgs::Point p;
00135 p.x = points[i].x();
00136 p.y = points[i].y();
00137 p.z = points[i].z();
00138 points_marker.points.push_back( p );
00139 }
00140
00141
00142 vm::InteractiveMarkerControl points_control;
00143 points_control.always_visible = true;
00144 points_control.interaction_mode = vm::InteractiveMarkerControl::NONE;
00145 points_control.markers.push_back( points_marker );
00146
00147
00148 int_marker.controls.push_back( points_control );
00149
00150 server_->insert( int_marker );
00151 }
00152
00153 void updatePointClouds()
00154 {
00155 std::vector<btVector3> points_in, points_out;
00156 points_in.reserve( points_.size() );
00157 points_out.reserve( points_.size() );
00158
00159
00160 for ( unsigned i=0; i<points_.size(); i++ )
00161 {
00162 if ( TestPointAgainstAabb2( min_sel_, max_sel_, points_[i] ) )
00163 {
00164 points_in.push_back( points_[i] );
00165 }
00166 else
00167 {
00168 points_out.push_back( points_[i] );
00169 }
00170 }
00171
00172 std_msgs::ColorRGBA in_color;
00173 in_color.r = 1.0;
00174 in_color.g = 0.8;
00175 in_color.b = 0.0;
00176 in_color.a = 1.0;
00177
00178 std_msgs::ColorRGBA out_color;
00179 out_color.r = 0.5;
00180 out_color.g = 0.5;
00181 out_color.b = 0.5;
00182 out_color.a = 1.0;
00183
00184 updatePointCloud( "selected_points", in_color, points_in );
00185 updatePointCloud( "unselected_points", out_color, points_out );
00186 }
00187
00188 void makeSizeHandles( )
00189 {
00190 for ( int axis=0; axis<3; axis++ )
00191 {
00192 for ( int sign=-1; sign<=1; sign+=2 )
00193 {
00194 vm::InteractiveMarker int_marker;
00195 int_marker.header.frame_id = "/base_link";
00196 int_marker.scale = 1.0;
00197
00198 vm::InteractiveMarkerControl control;
00199 control.interaction_mode = vm::InteractiveMarkerControl::MOVE_AXIS;
00200 control.orientation_mode = vm::InteractiveMarkerControl::INHERIT;
00201 control.always_visible = false;
00202
00203 control.orientation.w = 1;
00204
00205 switch ( axis )
00206 {
00207 case 0:
00208 int_marker.name = sign>0 ? "max_x" : "min_x";
00209 int_marker.pose.position.x = sign>0 ? max_sel_.x() : min_sel_.x();
00210 int_marker.pose.position.y = 0.5 * ( max_sel_.y() + min_sel_.y() );
00211 int_marker.pose.position.z = 0.5 * ( max_sel_.z() + min_sel_.z() );
00212 control.orientation.x = 1;
00213 control.orientation.y = 0;
00214 control.orientation.z = 0;
00215 break;
00216 case 1:
00217 int_marker.name = sign>0 ? "max_y" : "min_y";
00218 int_marker.pose.position.x = 0.5 * ( max_sel_.x() + min_sel_.x() );
00219 int_marker.pose.position.y = sign>0 ? max_sel_.y() : min_sel_.y();
00220 int_marker.pose.position.z = 0.5 * ( max_sel_.z() + min_sel_.z() );
00221 control.orientation.x = 0;
00222 control.orientation.y = 0;
00223 control.orientation.z = 1;
00224 break;
00225 default:
00226 int_marker.name = sign>0 ? "max_z" : "min_z";
00227 int_marker.pose.position.x = 0.5 * ( max_sel_.x() + min_sel_.x() );
00228 int_marker.pose.position.y = 0.5 * ( max_sel_.y() + min_sel_.y() );
00229 int_marker.pose.position.z = sign>0 ? max_sel_.z() : min_sel_.z();
00230 control.orientation.x = 0;
00231 control.orientation.y = -1;
00232 control.orientation.z = 0;
00233 break;
00234 }
00235
00236 interactive_markers::makeArrow( int_marker, control, 0.5 * sign );
00237
00238 int_marker.controls.push_back( control );
00239 server_->insert( int_marker, boost::bind( &PointCouldSelector::processAxisFeedback, this, _1 ) );
00240 }
00241 }
00242 }
00243
00244 void updateSizeHandles( )
00245 {
00246 for ( int axis=0; axis<3; axis++ )
00247 {
00248 for ( int sign=-1; sign<=1; sign+=2 )
00249 {
00250 std::string name;
00251 geometry_msgs::Pose pose;
00252
00253 switch ( axis )
00254 {
00255 case 0:
00256 name = sign>0 ? "max_x" : "min_x";
00257 pose.position.x = sign>0 ? max_sel_.x() : min_sel_.x();
00258 pose.position.y = 0.5 * ( max_sel_.y() + min_sel_.y() );
00259 pose.position.z = 0.5 * ( max_sel_.z() + min_sel_.z() );
00260 break;
00261 case 1:
00262 name = sign>0 ? "max_y" : "min_y";
00263 pose.position.x = 0.5 * ( max_sel_.x() + min_sel_.x() );
00264 pose.position.y = sign>0 ? max_sel_.y() : min_sel_.y();
00265 pose.position.z = 0.5 * ( max_sel_.z() + min_sel_.z() );
00266 break;
00267 default:
00268 name = sign>0 ? "max_z" : "min_z";
00269 pose.position.x = 0.5 * ( max_sel_.x() + min_sel_.x() );
00270 pose.position.y = 0.5 * ( max_sel_.y() + min_sel_.y() );
00271 pose.position.z = sign>0 ? max_sel_.z() : min_sel_.z();
00272 break;
00273 }
00274
00275 server_->setPose( name, pose );
00276 }
00277 }
00278 }
00279
00280 private:
00281 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server_;
00282
00283 btVector3 min_sel_, max_sel_;
00284 std::vector<btVector3> points_;
00285
00286 vm::InteractiveMarker sel_points_marker_;
00287 vm::InteractiveMarker unsel_points_marker_;
00288 };
00289
00290
00291
00292
00293 double rand( double min, double max )
00294 {
00295 double t = (double)rand() / (double)RAND_MAX;
00296 return min + t*(max-min);
00297 }
00298
00299
00300 void makePoints( std::vector<btVector3>& points_out, int num_points )
00301 {
00302 double radius = 3;
00303 double scale = 0.2;
00304 points_out.resize(num_points);
00305 for( int i = 0; i < num_points; i++ )
00306 {
00307 points_out[i].setX( scale * rand( -radius, radius ) );
00308 points_out[i].setY( scale * rand( -radius, radius ) );
00309 points_out[i].setZ( scale * radius * 0.2 * ( sin( 10.0 / radius * points_out[i].x() ) + cos( 10.0 / radius * points_out[i].y() ) ) );
00310 }
00311 }
00312
00313
00314 int main(int argc, char** argv)
00315 {
00316 ros::init(argc, argv, "selection");
00317
00318
00319 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> server(
00320 new interactive_markers::InteractiveMarkerServer("selection") );
00321
00322 std::vector<btVector3> points;
00323 makePoints( points, 10000 );
00324
00325 PointCouldSelector selector( server, points );
00326
00327
00328 server->applyChanges();
00329
00330
00331 ros::spin();
00332 }
00333