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 #include "pr2_gripper_click/gripper_click_grasp_adjust.h"
00031
00032
00033 #include <tf/transform_datatypes.h>
00034
00035 #include <geometry_msgs/PoseStamped.h>
00036
00037 #include <rviz/render_panel.h>
00038 #include <rviz/mesh_loader.h>
00039
00040 #include <OGRE/OgreEntity.h>
00041 #include <OGRE/OgreLight.h>
00042 #include <OGRE/OgreManualObject.h>
00043
00044 #include <rviz_interaction_tools/unique_string_manager.h>
00045 #include <rviz_interaction_tools/image_tools.h>
00046
00047 #include <pcl/io/io.h>
00048 #include <pcl/point_types.h>
00049
00050 #include <actionlib/client/simple_action_client.h>
00051 #include <pr2_grasp_adjust/GraspAdjustAction.h>
00052
00053 namespace pr2_gripper_click {
00054
00055 GripperClickGraspAdjust::GripperClickGraspAdjust() :
00056 GripperClickPlugin<GripperClickPickupAction>("Grasp Adjust"),
00057 gripper_index_(0),
00058 valid_transform_(false),
00059 action_client_("grasp_adjust_action_server_node", false)
00060 {
00061 if(!action_client_.waitForServer(ros::Duration(2.0)))
00062 ROS_ERROR("Couldn't communicate with grasp adjust action server... continuing anyway.");
00063 ROS_INFO("Initialized grasp_adjust plugin!");
00064 }
00065
00066
00067 GripperClickGraspAdjust::~GripperClickGraspAdjust()
00068 {
00069 scene_node_->getParent()->removeChild( scene_node_ );
00070 delete scene_node_;
00071 }
00072
00073
00074 void GripperClickGraspAdjust::init( rviz::VisualizationManager *vis_manager, Ogre::SceneManager* scene_manager, Ogre::SceneNode* camera_node )
00075 {
00076 scene_node_ = scene_manager->getRootSceneNode()->createChildSceneNode();
00077
00078
00079
00080 rviz_interaction_tools::UniqueStringManager usm;
00081
00082 line_object_ = scene_manager->createManualObject( usm.unique("GripperClickLineIndicator") );
00083
00084
00085 line_object_->setDynamic(true);
00086 line_object_->begin("BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP);
00087 line_object_->position(0.0, 0.0, 0.0);
00088 line_object_->position(0.0, 0.0, 0.0);
00089 line_object_->index(0);
00090 line_object_->index(1);
00091 line_object_->index(0);
00092 line_object_->end();
00093
00094 Ogre::AxisAlignedBox aabInf;
00095 aabInf.setInfinite();
00096 line_object_->setBoundingBox(aabInf);
00097
00098
00099 line_object_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY);
00100
00101 scene_manager->getRootSceneNode()->attachObject(line_object_);
00102 }
00103
00104 bool GripperClickGraspAdjust::setGoal( const GripperClickPickupGoal::ConstPtr &goal )
00105 {
00106 camera_info_ = goal->sensor_data.camera_info;
00107 disparity_image_ = goal->sensor_data.disparity_image;
00108 valid_transform_ = false;
00109
00110 setDescription("Please double-click on the desired object to compute a grasp.");
00111 return true;
00112 }
00113
00114
00115 void GripperClickGraspAdjust::show( )
00116 {
00117 scene_node_->setVisible(true);
00118 }
00119
00120 void GripperClickGraspAdjust::hide( )
00121 {
00122 scene_node_->setVisible(false);
00123 }
00124
00125 void GripperClickGraspAdjust::getGripperParams( bool &visible, Ogre::Vector3 &position, Ogre::Quaternion &orientation, float &angle )
00126 {
00127 visible = valid_transform_;
00128 if (visible)
00129 {
00130
00131
00132 btQuaternion rot = gripper_transform_[gripper_index_].getRotation();
00133 btVector3 trl = gripper_transform_[gripper_index_].getOrigin();
00134
00135 position = Ogre::Vector3(trl.x(), trl.y(), trl.z());
00136 orientation = Ogre::Quaternion(rot.w(), rot.x(), rot.y(), rot.z());
00137
00138 angle = gripper_angle_[gripper_index_];
00139 }
00140 }
00141
00142 void GripperClickGraspAdjust::update(float wall_dt, float ros_dt)
00143 {
00144 }
00145
00146 void GripperClickGraspAdjust::receiveGraspAdjustAction(const actionlib::SimpleClientGoalState &state,
00147 const pr2_grasp_adjust::GraspAdjustResultConstPtr &result)
00148 {
00149 gripper_index_ = 0;
00150 ROS_INFO("Received grasp adjust response with %d grasps", (int)result->grasp_poses.size());
00151 if(state.state_ == state.SUCCEEDED)
00152 {
00153 int num = result->grasp_poses.size();
00154
00155 gripper_transform_.resize(num);
00156 gripper_score_.resize(num);
00157 gripper_angle_.resize(num);
00158
00159 for(int i = 0; i < num; i++)
00160 {
00161 tf::poseMsgToTF(result->grasp_poses[i].pose, gripper_transform_[i]);
00162 gripper_angle_[i] = std::max( std::min(result->gripper_openings[i] , (float)0.541) , (float)0.0);
00163 gripper_score_[i] = result->grasp_scores[i];
00164 }
00165
00166 valid_transform_ = true;
00167 setDescription("Use your mouse to adjust the computed grasp.\n\nClick OK when your're finished.");
00168 }
00169 else
00170 {
00171 setDescription("Could not compute a valid grasp.\n\nTry to double-click on a different location to compute a new grasp.");
00172 }
00173 }
00174
00175 void GripperClickGraspAdjust::requestGraspAdjustAction()
00176 {
00177 valid_transform_ = false;
00178 gripper_index_ = 0;
00179 pcl::PointCloud<pcl::PointXYZ> cloud;
00180 cloud.header = disparity_image_.header;
00181 cloud.is_dense = false;
00182
00183 int seed_index = 0;
00184 int height = disparity_image_.image.height;
00185 int width = disparity_image_.image.width;
00186
00187 for(int x = 0; x < width; x++ )
00188 for(int y = 0; y < height; y++)
00189 if(rviz_interaction_tools::hasDisparityValue(disparity_image_, y, x))
00190 {
00191 if(abs(x - dlb_.x_) > width / 5 ) continue;
00192 if(abs(y - dlb_.y_) > height / 5 ) continue;
00193
00194 pcl::PointXYZ pt;
00195 rviz_interaction_tools::getPoint(disparity_image_, camera_info_, y, x, pt.x, pt.y, pt.z);
00196 cloud.push_back(pt);
00197 if( dlb_.x_ == x && dlb_.y_ == y)
00198 seed_index = cloud.size() - 1;
00199 }
00200
00201 pr2_grasp_adjust::GraspAdjustGoal goal;
00202 pcl::toROSMsg(cloud, goal.cloud);
00203
00204 goal.pose_stamped.header = disparity_image_.header;
00205 float px, py, pz;
00206 rviz_interaction_tools::getPoint(disparity_image_, camera_info_, dlb_.y_, dlb_.x_, px, py, pz);
00207 tf::pointTFToMsg(tf::Point(px, py, pz), goal.pose_stamped.pose.position);
00208 tf::quaternionTFToMsg(tf::Quaternion(0,0,0,1), goal.pose_stamped.pose.orientation);
00209 goal.use_orientation = false;
00210 goal.seed_index = seed_index;
00211 goal.cloud.header.stamp = ros::Time::now();
00212 goal.pose_stamped.header.stamp = goal.cloud.header.stamp;
00213
00214 action_client_.sendGoal(goal,
00215 boost::bind(&GripperClickGraspAdjust::receiveGraspAdjustAction, this, _1, _2),
00216 ActionClient::SimpleActiveCallback(),
00217 ActionClient::SimpleFeedbackCallback());
00218
00219 setDescription("Computing grasp..");
00220 }
00221
00222 void GripperClickGraspAdjust::onRenderWindowMouseEvents( wxMouseEvent& event, Ogre::Ray &mouse_ray )
00223 {
00224 int x = event.GetX();
00225 int y = event.GetY();
00226
00227 if (event.GetWheelRotation() >= event.GetWheelDelta())
00228 {
00229 if(valid_transform_)
00230 {
00231
00232 tf::Transform rotate = tf::Transform(tf::Quaternion(tf::Vector3(1, 0, 0), 0.1), tf::Vector3(0,0,0));
00233 gripper_transform_[gripper_index_] = gripper_transform_[gripper_index_] * rotate;
00234 }
00235
00236
00237
00238 }
00239
00240 if (event.GetWheelRotation() <= -event.GetWheelDelta())
00241 {
00242 if(valid_transform_)
00243 {
00244
00245 tf::Transform rotate = tf::Transform(tf::Quaternion(tf::Vector3(1, 0, 0), -0.1), tf::Vector3(0,0,0));
00246 gripper_transform_[gripper_index_] = gripper_transform_[gripper_index_] * rotate;
00247 }
00248 }
00249
00250 if (event.ButtonDClick(wxMOUSE_BTN_LEFT))
00251 {
00252 if (rviz_interaction_tools::hasDisparityValue(disparity_image_, y, x))
00253 {
00254 dlb_.x_ = x;
00255 dlb_.y_ = y;
00256
00257
00258 requestGraspAdjustAction();
00259 }
00260 }
00261
00262 if (event.ButtonDown(wxMOUSE_BTN_LEFT))
00263 {
00264 lb_.down_ = true;
00265 if(valid_transform_)
00266 {
00267 gripper_index_++;
00268 if(gripper_index_ >= gripper_transform_.size())
00269 gripper_index_ = 0;
00270 }
00271
00272
00273 }
00274 if (event.ButtonUp(wxMOUSE_BTN_LEFT)) lb_.down_ = false;
00275
00276 if (event.ButtonDown(wxMOUSE_BTN_RIGHT))
00277 {
00278 rb_.down_ = true;
00279 rb_.x_ = x;
00280 rb_.y_ = y;
00281
00282
00283
00284
00285
00286
00287
00288
00289 }
00290 if (event.ButtonUp(wxMOUSE_BTN_RIGHT)) rb_.down_ = false;
00291
00292 if (event.ButtonDown(wxMOUSE_BTN_MIDDLE))
00293 {
00294 mb_.down_ = true;
00295 mb_.x_ = x;
00296 mb_.y_ = y;
00297 if(valid_transform_)
00298 mb_.ref_ = gripper_angle_ [gripper_index_];
00299 }
00300 if (event.ButtonUp(wxMOUSE_BTN_MIDDLE)) mb_.down_ = false;
00301
00302 if (event.Dragging())
00303 {
00304 if (rb_.down_)
00305 {
00306 if(valid_transform_)
00307 {
00308
00309 int dy = rb_.y_ - y;
00310 rb_.y_ = y;
00311 float dt = rb_.ref_ + ((float)dy / 100.0) * 0.1;
00312 tf::Transform translate = tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(dt,0,0));
00313 gripper_transform_[gripper_index_] = gripper_transform_[gripper_index_] * translate ;
00314 }
00315
00316 }
00317 if (mb_.down_)
00318 {
00319 if(valid_transform_)
00320 {
00321
00322 int dy = y - mb_.y_;
00323 float da = ((float)dy/100.0) * 0.541;
00324 gripper_angle_[gripper_index_] = mb_.ref_ + da;
00325 gripper_angle_[gripper_index_] = std::min(gripper_angle_[gripper_index_] , (float)0.541);
00326 gripper_angle_[gripper_index_] = std::max(gripper_angle_[gripper_index_] , (float)0.0);
00327 }
00328 }
00329 if (lb_.down_)
00330 {
00331 lb_.x_ = dlb_.x_ - x;
00332 lb_.y_ = dlb_.y_ - y;
00333 }
00334 }
00335
00336 }
00337
00338 bool GripperClickGraspAdjust::getResult(GripperClickPickupResult &result)
00339 {
00340
00341 tf::poseTFToMsg(gripper_transform_[gripper_index_], result.grasp_pose.pose);
00342 result.grasp_pose.header.stamp = ros::Time::now();
00343 result.grasp_pose.header.frame_id = disparity_image_.header.frame_id;
00344 result.gripper_opening = gripper_angle_[gripper_index_] / 0.5 * 0.0857;
00345 ROS_INFO("gripper_angle_: %.3f, using gripper opening of %.3f", gripper_angle_[gripper_index_], result.gripper_opening);
00346 return true;
00347 }
00348
00349 }