00001 #include <visualization_msgs/InteractiveMarker.h>
00002 #include <visualization_msgs/InteractiveMarkerFeedback.h>
00003 #include <geometry_msgs/PoseStamped.h>
00004 #include <std_msgs/String.h>
00005 #include <tf/tf.h>
00006
00007 #include <jsk_interactive_marker/interactive_marker_helpers.h>
00008 #include <jsk_interactive_marker/interactive_point_cloud.h>
00009 #include <tf/transform_datatypes.h>
00010 #include <pcl_ros/transforms.h>
00011 #include <tf/transform_listener.h>
00012 #include <pcl_conversions/pcl_conversions.h>
00013
00014
00015 using namespace visualization_msgs;
00016 using namespace interactive_markers;
00017 using namespace im_helpers;
00018
00019 InteractivePointCloud::InteractivePointCloud(std::string marker_name,
00020 std::string topic_name, std::string server_name ):
00021 marker_name_(marker_name)
00022 , nh_()
00023 , pnh_("~")
00024 , tfl_(nh_)
00025 , marker_server_(topic_name, server_name, false)
00026 {
00027
00028 pnh_.param<double>("point_size", point_size_, 0.004);
00029 pnh_.param<std::string>("input", input_pointcloud_, "/selected_pointcloud");
00030
00031 pnh_.param<bool>("use_bounding_box", use_bounding_box_, "true");
00032 pnh_.param<std::string>("input_bounding_box", input_bounding_box_, "/bounding_box_marker/selected_box_array");
00033 pnh_.param<std::string>("handle_pose", initial_handle_pose_, "/handle_estimator/output_best");
00034
00035
00036 pub_click_point_ = pnh_.advertise<geometry_msgs::PointStamped>("right_click_point", 1);
00037 pub_left_click_ = pnh_.advertise<geometry_msgs::PointStamped>("left_click_point", 1);
00038 pub_marker_pose_ = pnh_.advertise<geometry_msgs::PoseStamped>("marker_pose", 1);
00039 pub_grasp_pose_ = pnh_.advertise<geometry_msgs::PoseStamped>("grasp_pose", 1);
00040 pub_box_movement_ = pnh_.advertise<jsk_pcl_ros::BoundingBoxMovement>("box_movement", 1);
00041 pub_handle_pose_ = pnh_.advertise<geometry_msgs::PoseStamped>("handle_pose", 1);
00042 pub_handle_pose_array_ = pnh_.advertise<geometry_msgs::PoseArray>("handle_pose_array", 1);
00043
00044
00045 sub_handle_pose_ = pnh_.subscribe<geometry_msgs::PoseStamped> ("set_handle_pose", 1, boost::bind( &InteractivePointCloud::setHandlePoseCallback, this, _1));
00046
00047 sub_point_cloud_.subscribe(pnh_, input_pointcloud_, 1);
00048
00049
00050 if(use_bounding_box_){
00051
00052 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(10);
00053 sub_bounding_box_.subscribe(pnh_,input_bounding_box_, 1);
00054 sub_initial_handle_pose_.subscribe(pnh_, initial_handle_pose_, 1);
00055 sync_->connectInput(sub_point_cloud_, sub_bounding_box_, sub_initial_handle_pose_);
00056 sync_->registerCallback(boost::bind(&InteractivePointCloud::pointCloudAndBoundingBoxCallback, this, _1, _2, _3));
00057
00058 }else{
00059 sub_point_cloud_.registerCallback(&InteractivePointCloud::pointCloudCallback, this);
00060 }
00061 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (pnh_);
00062 dynamic_reconfigure::Server<Config>::CallbackType f =
00063 boost::bind (&InteractivePointCloud::configCallback, this, _1, _2);
00064 srv_->setCallback (f);
00065
00066 makeMenu();
00067 }
00068
00069 InteractivePointCloud::~InteractivePointCloud(){};
00070
00071 void InteractivePointCloud::configCallback(Config &config, uint32_t level)
00072 {
00073 boost::mutex::scoped_lock(mutex_);
00074 point_size_ = config.point_size;
00075 }
00076
00077 void InteractivePointCloud::pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud){
00078 makeMarker(cloud, point_size_ );
00079 }
00080
00081 void InteractivePointCloud::pointCloudAndBoundingBoxCallback(const sensor_msgs::PointCloud2ConstPtr &cloud, const jsk_pcl_ros::BoundingBoxArrayConstPtr &box, const geometry_msgs::PoseStampedConstPtr &handle){
00082 makeMarker(cloud, box, handle, point_size_ );
00083 }
00084
00085
00086
00087 void InteractivePointCloud::setHandlePoseCallback(const geometry_msgs::PoseStampedConstPtr &ps){
00088 if( ps->header.stamp == current_box_.header.stamp ){
00089 if(current_box_.boxes.size() > 0){
00090 handle_pose_ = *ps;
00091
00092 tf::Transform tf_ps, tf_box;
00093 tf_ps.setOrigin(tf::Vector3(ps->pose.position.x, ps->pose.position.y, ps->pose.position.z));
00094 tf_ps.setRotation(tf::Quaternion( ps->pose.orientation.x, ps->pose.orientation.y, ps->pose.orientation.z, ps->pose.orientation.w));
00095
00096 geometry_msgs::Pose pose = current_box_.boxes[0].pose;
00097 tf_box.setOrigin(tf::Vector3(pose.position.x, pose.position.y, pose.position.z));
00098 tf_box.setRotation(tf::Quaternion( pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w));
00099
00100 handle_tf_ = tf_box.inverseTimes(tf_ps);
00101 exist_handle_tf_ = true;
00102 publishHandPose( marker_pose_ );
00103
00104
00105 geometry_msgs::Pose handle_pose;
00106 handle_pose.position.x = handle_tf_.getOrigin().x();
00107 handle_pose.position.y = handle_tf_.getOrigin().y();
00108 handle_pose.position.z = handle_tf_.getOrigin().z();
00109 handle_pose.orientation.x = handle_tf_.getRotation().x();
00110 handle_pose.orientation.y = handle_tf_.getRotation().y();
00111 handle_pose.orientation.z = handle_tf_.getRotation().z();
00112 handle_pose.orientation.w = handle_tf_.getRotation().w();
00113
00114 box_movement_.handle_pose = handle_pose;
00115 }
00116 }
00117 }
00118
00119
00120 void InteractivePointCloud::makeMenu()
00121 {
00122 menu_handler_.insert( "Move", boost::bind( &InteractivePointCloud::move, this, _1) );
00123
00124 menu_handler_.insert( "Hide", boost::bind( &InteractivePointCloud::hide, this, _1));
00125 }
00126
00127
00128 void InteractivePointCloud::move( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback ){
00129 box_movement_.destination = marker_pose_;
00130 pub_box_movement_.publish(box_movement_);
00131
00132 }
00133
00134 void InteractivePointCloud::leftClickPoint( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00135 {
00136 if(!feedback->mouse_point_valid)
00137 {
00138 ROS_WARN("Clicked point had an invalid position. Not looking there!");
00139 return;
00140 }
00141
00142 ROS_DEBUG_STREAM_NAMED("cloud_handler", "Button click in frame "
00143 << feedback->header.frame_id << " at point\n" << feedback->mouse_point );
00144 geometry_msgs::PointStamped click_point;
00145 click_point.point = feedback->mouse_point;
00146 click_point.header = feedback->header;
00147 click_point.header.stamp = ros::Time::now();
00148 pub_left_click_.publish(click_point);
00149 }
00150
00151 void InteractivePointCloud::hide( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
00152 {
00153 marker_server_.erase(marker_name_);
00154 marker_server_.applyChanges();
00155 }
00156
00157
00158 void InteractivePointCloud::markerFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback){
00159 marker_pose_.pose = feedback->pose;
00160 marker_pose_.header = feedback->header;
00161 if(exist_handle_tf_){
00162 publishHandPose( marker_pose_);
00163 }
00164 }
00165
00166 void InteractivePointCloud::publishGraspPose(){
00167 pub_grasp_pose_.publish(handle_pose_);
00168 }
00169
00170 void InteractivePointCloud::publishHandPose( geometry_msgs::PoseStamped box_pose){
00171 tf::Transform tf_marker;
00172 tf_marker.setOrigin(tf::Vector3(box_pose.pose.position.x, box_pose.pose.position.y, box_pose.pose.position.z));
00173 tf_marker.setRotation(tf::Quaternion( box_pose.pose.orientation.x, box_pose.pose.orientation.y, box_pose.pose.orientation.z, box_pose.pose.orientation.w));
00174
00175 tf_marker = tf_marker * handle_tf_;
00176 geometry_msgs::PoseStamped handle_pose;
00177 handle_pose.header.frame_id = box_pose.header.frame_id;
00178 handle_pose.pose.position.x = tf_marker.getOrigin().x();
00179 handle_pose.pose.position.y = tf_marker.getOrigin().y();
00180 handle_pose.pose.position.z = tf_marker.getOrigin().z();
00181 handle_pose.pose.orientation.x = tf_marker.getRotation().x();
00182 handle_pose.pose.orientation.y = tf_marker.getRotation().y();
00183 handle_pose.pose.orientation.z = tf_marker.getRotation().z();
00184 handle_pose.pose.orientation.w = tf_marker.getRotation().w();
00185
00186 pub_handle_pose_.publish(handle_pose);
00187
00188 geometry_msgs::PoseArray handle_pose_array;
00189 handle_pose_array.header = handle_pose.header;
00190 handle_pose_array.poses.push_back(handle_pose.pose);
00191 pub_handle_pose_array_.publish(handle_pose_array);
00192 }
00193
00194 void InteractivePointCloud::makeMarker(const sensor_msgs::PointCloud2ConstPtr cloud,float size){
00195 makeMarker(cloud, jsk_pcl_ros::BoundingBoxArray::ConstPtr(), geometry_msgs::PoseStamped::ConstPtr(), size);
00196 }
00197 void InteractivePointCloud::makeMarker(const sensor_msgs::PointCloud2ConstPtr cloud, const jsk_pcl_ros::BoundingBoxArrayConstPtr box, const geometry_msgs::PoseStampedConstPtr handle, float size)
00198 {
00199 exist_handle_tf_ = false;
00200 current_croud_ = *cloud;
00201 current_box_ = *box;
00202
00203
00204 InteractiveMarker int_marker;
00205 int_marker.name = marker_name_;
00206
00207 pcl::PointCloud<PointT> pcl_cloud, transform_cloud;
00208 pcl::fromROSMsg(*cloud, pcl_cloud);
00209
00210 if(box && box->boxes.size() > 0){
00211 jsk_pcl_ros::BoundingBox first_box = box->boxes[0];
00212 int_marker.pose = first_box.pose;
00213 int_marker.header.frame_id = first_box.header.frame_id;
00214
00215 marker_pose_.header = box->header;
00216 marker_pose_.pose = first_box.pose;
00217
00218 tf::Transform transform;
00219 tf::poseMsgToTF(first_box.pose, transform);
00220
00221 pcl_ros::transformPointCloud(pcl_cloud, transform_cloud, transform.inverse());
00222 pcl_cloud = transform_cloud;
00223
00224 box_movement_.box = first_box;
00225 box_movement_.header.frame_id = first_box.header.frame_id;
00226
00227 if(handle->header.frame_id != ""){
00228 setHandlePoseCallback(handle);
00229 }
00230 }
00231
00232
00233 int num_points = pcl_cloud.points.size();
00234
00235 Marker marker;
00236 marker.color.r = 1.0;
00237 marker.color.g = 1.0;
00238 marker.color.b = 1.0;
00239 marker.color.a = 1.0;
00240 marker.frame_locked = false;
00241 if(num_points > 0)
00242 {
00243
00244 int_marker.header = cloud->header;
00245
00246 InteractiveMarkerControl control;
00247 control.always_visible = true;
00248
00249 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_3D;
00250 control.orientation_mode = visualization_msgs::InteractiveMarkerControl::INHERIT;
00251
00252 int_marker.header.stamp = ros::Time::now();
00253
00254 marker.scale.x = size;
00255 marker.scale.y = size;
00256 marker.scale.z = size;
00257 marker.type = visualization_msgs::Marker::SPHERE_LIST;
00258
00259 marker.points.resize( num_points );
00260 marker.colors.resize( num_points );
00261
00262 for ( int i=0; i<num_points; i++)
00263 {
00264 marker.points[i].x = pcl_cloud.points[i].x;
00265 marker.points[i].y = pcl_cloud.points[i].y;
00266 marker.points[i].z = pcl_cloud.points[i].z;
00267 marker.colors[i].r = pcl_cloud.points[i].r/255.;
00268 marker.colors[i].g = pcl_cloud.points[i].g/255.;
00269 marker.colors[i].b = pcl_cloud.points[i].b/255.;
00270 marker.colors[i].a = 1.0;
00271 }
00272 control.markers.push_back( marker );
00273
00274
00275 if(box && box->boxes.size() > 0){
00276 Marker bounding_box_marker;
00277 bounding_box_marker.color.r = 0.0;
00278 bounding_box_marker.color.g = 0.0;
00279 bounding_box_marker.color.b = 1.0;
00280 bounding_box_marker.color.a = 1.0;
00281 bounding_box_marker.type = visualization_msgs::Marker::LINE_LIST;
00282 bounding_box_marker.scale.x = 0.01;
00283 bounding_box_marker.points.resize(24);
00284
00285 double x = box->boxes[0].dimensions.x / 2;
00286 double y = box->boxes[0].dimensions.y / 2;
00287 double z = box->boxes[0].dimensions.z / 2;
00288 for(int i=0; i<4; i++)
00289 {
00290 if(i%2 == 0){
00291 bounding_box_marker.points[2*i].x = bounding_box_marker.points[2*i+1].x = x;
00292
00293 }else{
00294 bounding_box_marker.points[2*i].x = bounding_box_marker.points[2*i+1].x = - x;
00295 }
00296 if(i%4 < 2){
00297 bounding_box_marker.points[2*i].y = bounding_box_marker.points[2*i+1].y = y;
00298
00299 }else{
00300 bounding_box_marker.points[2*i].y = bounding_box_marker.points[2*i+1].y = - y;
00301
00302 }
00303 bounding_box_marker.points[2*i].z = z;
00304 bounding_box_marker.points[2*i+1].z = - z;
00305 }
00306
00307 for(int i=4; i<8; i++)
00308 {
00309 if(i%2 == 0){
00310 bounding_box_marker.points[2*i].x = bounding_box_marker.points[2*i+1].x = x;
00311
00312 }else{
00313 bounding_box_marker.points[2*i].x = bounding_box_marker.points[2*i+1].x = - x;
00314 }
00315 if(i%4 < 2){
00316 bounding_box_marker.points[2*i].z = bounding_box_marker.points[2*i+1].z = z;
00317
00318 }else{
00319 bounding_box_marker.points[2*i].z = bounding_box_marker.points[2*i+1].z = - z;
00320
00321 }
00322 bounding_box_marker.points[2*i].y = y;
00323 bounding_box_marker.points[2*i+1].y = - y;
00324 }
00325
00326 for(int i=8; i<12; i++)
00327 {
00328 if(i%2 == 0){
00329 bounding_box_marker.points[2*i].z = bounding_box_marker.points[2*i+1].z = z;
00330
00331 }else{
00332 bounding_box_marker.points[2*i].z = bounding_box_marker.points[2*i+1].z = - z;
00333 }
00334 if(i%4 < 2){
00335 bounding_box_marker.points[2*i].y = bounding_box_marker.points[2*i+1].y = y;
00336
00337 }else{
00338 bounding_box_marker.points[2*i].y = bounding_box_marker.points[2*i+1].y = - y;
00339
00340 }
00341 bounding_box_marker.points[2*i].x = x;
00342 bounding_box_marker.points[2*i+1].x = - x;
00343 }
00344
00345 control.markers.push_back( bounding_box_marker );
00346 }
00347 int_marker.controls.push_back( control );
00348
00349 addVisible6DofControl(int_marker);
00350
00351 marker_server_.insert( int_marker, boost::bind( &InteractivePointCloud::leftClickPoint, this, _1 ),
00352 visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
00353 marker_server_.setCallback( int_marker.name,
00354 boost::bind( &InteractivePointCloud::markerFeedback, this, _1) );
00355
00356 menu_handler_.apply( marker_server_, marker_name_ );
00357 marker_server_.applyChanges();
00358 ROS_INFO("made interactive point cloud");
00359
00360 publishGraspPose();
00361 }
00362 }