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_line.h"
00031
00032 #include <OGRE/OgreManualObject.h>
00033
00034 #include <rviz/render_panel.h>
00035
00036 #include <tf/transform_datatypes.h>
00037
00038 #include <geometry_msgs/PoseStamped.h>
00039
00040 #include <rviz_interaction_tools/unique_string_manager.h>
00041 #include <rviz_interaction_tools/image_tools.h>
00042
00043 namespace pr2_gripper_click {
00044
00045 GripperClickLine::GripperClickLine() :
00046 GripperClickPlugin<GripperClickPickupAction>("Line Drawing")
00047 {
00048 click_info_.valid_ = false;
00049 }
00050
00051
00052 void GripperClickLine::init( rviz::VisualizationManager *vis_manager, Ogre::SceneManager* scene_manager, Ogre::SceneNode* camera_node )
00053 {
00054 rviz_interaction_tools::UniqueStringManager usm;
00055
00056 line_object_ = vis_manager->getSceneManager()->createManualObject( usm.unique("GripperClickLineIndicator") );
00057 line_object_->setUseIdentityProjection(true);
00058 line_object_->setUseIdentityView(true);
00059 line_object_->setDynamic(true);
00060 line_object_->begin("BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP);
00061 line_object_->position(0.0, 0.0, 0.0);
00062 line_object_->position(0.0, 0.0, 0.0);
00063 line_object_->index(0);
00064 line_object_->index(1);
00065 line_object_->index(0);
00066 line_object_->end();
00067
00068 Ogre::AxisAlignedBox aabInf;
00069 aabInf.setInfinite();
00070 line_object_->setBoundingBox(aabInf);
00071
00072
00073 line_object_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY);
00074 scene_manager->getRootSceneNode()->attachObject(line_object_);
00075 }
00076
00077
00078 bool GripperClickLine::setGoal( const GripperClickPickupGoal::ConstPtr &goal )
00079 {
00080 camera_info_ = goal->sensor_data.camera_info;
00081 disparity_image_ = goal->sensor_data.disparity_image;
00082
00083 click_info_.valid_ = false;
00084 click_info_.down_x_ = click_info_.down_y_ = 0;
00085 click_info_.up_x_ = click_info_.up_y_ = 0;
00086
00087 setDescription( "Click and drag the mouse to set the desired gripper position and rotation.\n\nPress OK when you are finished." );
00088 return true;
00089 }
00090
00091
00092 void GripperClickLine::show( )
00093 {
00094 line_object_->setVisible( true );
00095 }
00096
00097 void GripperClickLine::hide( )
00098 {
00099 line_object_->setVisible( false );
00100 }
00101
00102 void GripperClickLine::getGripperParams( bool &visible, Ogre::Vector3 &position, Ogre::Quaternion &orientation, float &angle )
00103 {
00104 visible = hasValidResult();
00105 if ( visible )
00106 {
00107 computeTransform();
00108
00109
00110
00111
00112 btQuaternion rot = gripper_transform_.getRotation();
00113 btVector3 trl = gripper_transform_.getOrigin();
00114
00115 position = Ogre::Vector3(trl.x(), trl.y(), trl.z());
00116 orientation = Ogre::Quaternion(rot.w(), rot.x(), rot.y(), rot.z());
00117
00118 angle = gripper_angle_;
00119 }
00120 }
00121
00122
00123 void GripperClickLine::update(float wall_dt, float ros_dt)
00124 {
00125 float c_x = click_info_.down_x_ / ((float)disparity_image_.image.width / 2.0 ) - 1.0;
00126 float c_y = - (click_info_.down_y_ / ((float)disparity_image_.image.height / 2.0 ) - 1.0);
00127 float u_x = click_info_.up_x_ / ((float)disparity_image_.image.width / 2.0 ) - 1.0;
00128 float u_y = - (click_info_.up_y_ / ((float)disparity_image_.image.height / 2.0 ) - 1.0);
00129 float d_x = u_x - c_x;
00130 float d_y = u_y - c_y;
00131
00132 line_object_->beginUpdate(0);
00133 line_object_->position(c_x-d_x, c_y-d_y, 0.0);
00134 line_object_->position(c_x+d_x, c_y+d_y, 0.0);
00135 line_object_->index(0);
00136 line_object_->index(1);
00137 line_object_->index(0);
00138 line_object_->end();
00139 }
00140
00141 void GripperClickLine::onRenderWindowMouseEvents( wxMouseEvent& event, Ogre::Ray &mouse_ray )
00142 {
00143 int x = event.GetX();
00144 int y = event.GetY();
00145
00146 if (event.ButtonDown(wxMOUSE_BTN_LEFT))
00147 {
00148 if (rviz_interaction_tools::hasDisparityValue(disparity_image_, y, x))
00149 {
00150 ROS_INFO("Good click");
00151 click_info_.lbutton_down_ = true;
00152 click_info_.down_x_ = x;
00153 click_info_.down_y_ = y;
00154 click_info_.up_x_ = x;
00155 click_info_.up_y_ = y;
00156 }
00157 else ROS_INFO("Bad click");
00158 }
00159 if (event.ButtonUp(wxMOUSE_BTN_LEFT))
00160 {
00161 if (click_info_.lbutton_down_)
00162 {
00163 click_info_.lbutton_down_ = false;
00164 }
00165 }
00166 if (event.Dragging())
00167 {
00168 if (click_info_.lbutton_down_)
00169 {
00170 click_info_.up_x_ = x;
00171 click_info_.up_y_ = y;
00172 if (click_info_.up_x_ != click_info_.down_x_ ||
00173 click_info_.up_y_ != click_info_.down_y_ )
00174 {
00175 click_info_.valid_ = true;
00176 }
00177 }
00178 }
00179 }
00180
00181 bool GripperClickLine::hasValidResult()
00182 {
00183 if( !click_info_.valid_ || (click_info_.up_x_ == click_info_.down_x_ &&
00184 click_info_.up_y_ == click_info_.down_y_ ) )
00185 {
00186 return false;
00187 }
00188 return true;
00189 }
00190
00191 bool GripperClickLine::computeTransform()
00192 {
00193 if ( !hasValidResult() )
00194 {
00195 return false;
00196 }
00197
00198 float px, py, pz;
00199 rviz_interaction_tools::getPoint(disparity_image_, camera_info_,
00200 click_info_.down_y_, click_info_.down_x_,
00201 px, py, pz);
00202 btVector3 grasp_point(px, py, pz);
00203 float depth = grasp_point.z();
00204 btVector3 grasp_direction = grasp_point;
00205 grasp_direction.normalize();
00206
00207 grasp_point = grasp_point - 0.13 * grasp_direction;
00208
00209
00210 btVector3 x_dir = grasp_direction;
00211
00212
00213
00214 float delta_x = click_info_.up_x_ - click_info_.down_x_;
00215 float delta_y = click_info_.up_y_ - click_info_.down_y_;
00216 btVector3 y_dir(delta_x,
00217 delta_y,
00218 0);
00219 y_dir.normalize();
00220
00221
00222 btVector3 z_dir = x_dir.cross(y_dir);
00223 z_dir.normalize();
00224 y_dir = z_dir.cross(x_dir);
00225
00226
00227 btMatrix3x3 rot( x_dir.x(), x_dir.y(), x_dir.z(),
00228 y_dir.x(), y_dir.y(), y_dir.z(),
00229 z_dir.x(), z_dir.y(), z_dir.z() );
00230 rot = rot.transpose();
00231 btTransform grasp_tran(rot, grasp_point);
00232
00233 gripper_transform_ = grasp_tran;
00234
00235 float half_line_len = sqrt(delta_x*delta_x + delta_y*delta_y);
00236 float f = camera_info_.P[0];
00237 float gripper_opening = 2 * depth * half_line_len / f / 0.0857 * 0.5;
00238 if(gripper_opening > .5) gripper_opening = .5;
00239
00240 gripper_angle_ = gripper_opening;
00241 return true;
00242 }
00243
00244 bool GripperClickLine::getResult(GripperClickPickupResult &result)
00245 {
00246 if ( !hasValidResult() )
00247 {
00248 return false;
00249 }
00250
00251 computeTransform();
00252
00253 tf::poseTFToMsg(gripper_transform_, result.grasp_pose.pose);
00254 result.grasp_pose.header.stamp = ros::Time::now();
00255 result.grasp_pose.header.frame_id = disparity_image_.header.frame_id;
00256
00257 result.gripper_opening = gripper_angle_;
00258
00259 return true;
00260 }
00261
00262 }