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_place_cartesian.h"
00031
00032 #include <OGRE/OgreManualObject.h>
00033
00034 #include <rviz/render_panel.h>
00035 #include <rviz/common.h>
00036
00037 #include <tf/transform_datatypes.h>
00038
00039 #include <geometry_msgs/PoseStamped.h>
00040
00041 #include <rviz_interaction_tools/unique_string_manager.h>
00042 #include <rviz_interaction_tools/image_tools.h>
00043
00044 namespace pr2_gripper_click {
00045
00046 GripperClickPlaceCartesian::GripperClickPlaceCartesian() :
00047 GripperClickPlugin<GripperClickPlaceAction>("Cartesian Control"),
00048 initialized_(false)
00049 {
00050 }
00051
00052 void GripperClickPlaceCartesian::init( rviz::VisualizationManager *vis_manager,
00053 Ogre::SceneManager* scene_manager,
00054 Ogre::SceneNode* camera_node )
00055 {
00056 camera_node_ = camera_node;
00057
00058 rviz_interaction_tools::UniqueStringManager usm;
00059
00060 cartesian_control_ = new rviz_interaction_tools::CartesianControl( scene_manager->getRootSceneNode(), vis_manager );
00061 cartesian_control_->setFixedControlsOrientation(true);
00062 cartesian_control_->hide();
00063
00064 point_cloud_ = new ogre_tools::PointCloud();
00065
00066 gripper_scene_node_ = scene_manager->getRootSceneNode()->createChildSceneNode();
00067 gripper_scene_node_->attachObject( point_cloud_ );
00068
00069 main_win_point_cloud_ = new ogre_tools::PointCloud();
00070
00071 main_win_object_scene_node_ = vis_manager->getSceneManager()->getRootSceneNode()->createChildSceneNode();
00072 main_win_object_scene_node_->attachObject( main_win_point_cloud_ );
00073 }
00074
00075
00076
00077 void GripperClickPlaceCartesian::show( )
00078 {
00079 main_win_object_scene_node_->setVisible(initialized_);
00080 main_win_point_cloud_->setVisible(initialized_);
00081 gripper_scene_node_->setVisible(initialized_);
00082 if ( initialized_ )
00083 {
00084 cartesian_control_->show();
00085 if ( !main_win_point_cloud_->isAttached() )
00086 {
00087 main_win_object_scene_node_->attachObject( main_win_point_cloud_ );
00088 }
00089 if ( !point_cloud_->isAttached() )
00090 {
00091 gripper_scene_node_->attachObject( point_cloud_ );
00092 }
00093 }
00094 }
00095
00096 void GripperClickPlaceCartesian::hide( )
00097 {
00098 main_win_object_scene_node_->setVisible(false);
00099 main_win_point_cloud_->detachFromParent();
00100 point_cloud_->detachFromParent();
00101 gripper_scene_node_->setVisible(false);
00102 cartesian_control_->hide();
00103 }
00104
00105 bool GripperClickPlaceCartesian::setGoal( const GripperClickPlaceGoal::ConstPtr &goal )
00106 {
00107 camera_info_ = goal->sensor_data.camera_info;
00108 disparity_image_ = goal->sensor_data.disparity_image;
00109
00110 point_cloud_->clear();
00111 main_win_point_cloud_->clear();
00112
00113 ROS_INFO("Place click received grasp orientation: %f %f %f %f, default object orientation %f %f %f %f",
00114 goal->grasp_pose.orientation.w, goal->grasp_pose.orientation.x,
00115 goal->grasp_pose.orientation.y, goal->grasp_pose.orientation.z,
00116 goal->default_orientation.w, goal->default_orientation.x,
00117 goal->default_orientation.y, goal->default_orientation.z);
00118
00119
00120 object_orientation_ = Ogre::Quaternion( goal->default_orientation.w, goal->default_orientation.x,
00121 goal->default_orientation.y, goal->default_orientation.z );
00122 if (object_orientation_.Norm() < 1.0e-5)
00123 {
00124 ROS_WARN("Gripper click place received 0-length quaternion for default object orientation. Using identity.");
00125 object_orientation_ = Ogre::Quaternion(1, 0, 0, 0);
00126 }
00127
00128
00129
00130 gripper_orientation_ = Ogre::Quaternion( goal->grasp_pose.orientation.w, goal->grasp_pose.orientation.x,
00131 goal->grasp_pose.orientation.y, goal->grasp_pose.orientation.z );
00132 if (gripper_orientation_.Norm() < 1.0e-5)
00133 {
00134 ROS_WARN("Gripper click place received 0-length quaternion for grasp orientation. Using identity.");
00135 gripper_orientation_ = Ogre::Quaternion(1, 0, 0, 0);
00136 }
00137 gripper_position_ = Ogre::Vector3(goal->grasp_pose.position.x, goal->grasp_pose.position.y,
00138 goal->grasp_pose.position.z);
00139
00140 rviz::robotToOgre( gripper_orientation_ );
00141 rviz::robotToOgre( gripper_position_ );
00142
00143
00144 if ( goal->object.cluster.points.size() > 0 && (goal->object.cluster.header.frame_id == "r_wrist_roll_link" ||
00145 goal->object.cluster.header.frame_id == "l_wrist_roll_link") )
00146 {
00147 ROS_DEBUG_STREAM( "Received " << goal->object.cluster.points.size() <<
00148 " points in frame " << goal->object.cluster.header.frame_id );
00149
00150
00151 if (goal->object.cluster.header.frame_id !="r_wrist_roll_link" &&
00152 goal->object.cluster.header.frame_id !="l_wrist_roll_link")
00153 {
00154 ROS_ERROR("Gripper place with object only works if cloud is in {l,r}_wrist_roll_link");
00155 return false;
00156 }
00157 gripper_orientation_ = Ogre::Quaternion(1, 0, 0, 0);
00158 object_orientation_ = Ogre::Quaternion(1, 0, 0, 0);
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173 std::vector<ogre_tools::PointCloud::Point> raw_points;
00174 raw_points.resize( goal->object.cluster.points.size() );
00175
00176 Ogre::Vector3 mean(0,0,0);
00177
00178 for ( unsigned i=0; i<goal->object.cluster.points.size(); i++ )
00179 {
00180 raw_points[i].x = goal->object.cluster.points[i].x;
00181 raw_points[i].y = goal->object.cluster.points[i].y;
00182 raw_points[i].z = goal->object.cluster.points[i].z;
00183 raw_points[i].setColor( 1, 0, 0 );
00184
00185 mean += Ogre::Vector3( goal->object.cluster.points[i].x,
00186 goal->object.cluster.points[i].y,
00187 goal->object.cluster.points[i].z );
00188 }
00189
00190 mean /= raw_points.size();
00191 gripper_position_ = -1.0 * mean;
00192
00193 ROS_INFO( "point cloud has %d extra channels", (int)goal->object.cluster.channels.size() );
00194
00195
00196 for( unsigned c=0; c<goal->object.cluster.channels.size(); c++)
00197 {
00198 if ( goal->object.cluster.channels[c].values.size() != goal->object.cluster.points.size() )
00199 {
00200 continue;
00201 }
00202
00203 ROS_INFO( "channel %d: %s", c, goal->object.cluster.channels[c].name.c_str() );
00204
00205 if ( goal->object.cluster.channels[c].name == "intensity" )
00206 {
00207 for ( unsigned i=0; i<goal->object.cluster.points.size(); i++ )
00208 {
00209 raw_points[i].setColor( goal->object.cluster.channels[c].values[i],
00210 goal->object.cluster.channels[c].values[i],
00211 goal->object.cluster.channels[c].values[i] );
00212 }
00213 }
00214 if ( goal->object.cluster.channels[c].name == "rgb" )
00215 {
00216 for ( unsigned i=0; i<goal->object.cluster.points.size(); i++ )
00217 {
00218 raw_points[i].color = *( (uint32_t*) & (goal->object.cluster.channels[c].values[i]) );
00219 }
00220 }
00221 }
00222
00223 point_cloud_->addPoints( &raw_points[0], raw_points.size() );
00224 main_win_point_cloud_->addPoints( &raw_points[0], raw_points.size() );
00225 }
00226
00227 hide();
00228 initialized_ = false;
00229
00230 setDescription("Please double-click at the spot where you want to place the object.");
00231 return true;
00232 }
00233
00234 void GripperClickPlaceCartesian::update(float wall_dt, float ros_dt)
00235 {
00236 cartesian_control_->update();
00237
00238 gripper_scene_node_->setPosition( cartesian_control_->getPosition() );
00239 gripper_scene_node_->setOrientation( cartesian_control_->getOrientation() );
00240 main_win_object_scene_node_->setPosition( cartesian_control_->getPosition() );
00241 main_win_object_scene_node_->setOrientation( cartesian_control_->getOrientation() );
00242 }
00243
00244 void GripperClickPlaceCartesian::onRenderWindowMouseEvents( wxMouseEvent& event, Ogre::Ray &mouse_ray )
00245 {
00246 int x = event.GetX();
00247 int y = event.GetY();
00248
00249 if ( !initialized_ )
00250 {
00251 if ( event.ButtonDown(wxMOUSE_BTN_LEFT) && rviz_interaction_tools::hasDisparityValue(disparity_image_, y, x))
00252 {
00253 float px, py, pz;
00254 rviz_interaction_tools::getPoint(disparity_image_, camera_info_, y, x, px, py, pz);
00255
00256 Ogre::Vector3 controls_position(px,py,pz);
00257 controls_position = camera_node_->getPosition() + camera_node_->getOrientation()*controls_position;
00258
00259
00260 Ogre::Quaternion controls_orientation( Ogre::Degree( 45 ), Ogre::Vector3(0,1,0) );
00261
00262
00263 Ogre::Vector3 gripper_position = controls_position + object_orientation_ * gripper_position_;
00264 Ogre::Quaternion gripper_orientation = object_orientation_ * gripper_orientation_;
00265
00266 cartesian_control_->setPosition( gripper_position );
00267 cartesian_control_->setOrientation( gripper_orientation );
00268
00269 cartesian_control_->setControlsPosition( controls_position );
00270 cartesian_control_->setControlsOrientation( controls_orientation );
00271
00272 setDescription("Use the box handles to drag the gripper and the wheels to turn it. You can reset the position by double-clicking on the desired location.\n\nPress OK When you are finished.");
00273 initialized_ = true;
00274 show();
00275 }
00276 }
00277 else
00278 {
00279 if ( event.ButtonDown(wxMOUSE_BTN_LEFT) )
00280 {
00281 cartesian_control_->mouseDown( mouse_ray );
00282 }
00283 if ( event.ButtonUp(wxMOUSE_BTN_LEFT) )
00284 {
00285 cartesian_control_->mouseUp( mouse_ray );
00286 }
00287 else
00288 {
00289 cartesian_control_->mouseMove( mouse_ray );
00290 }
00291 }
00292 }
00293
00294 bool GripperClickPlaceCartesian::hasValidResult()
00295 {
00296 return initialized_;
00297 }
00298
00299
00300 bool GripperClickPlaceCartesian::getResult(GripperClickPlaceResult &result)
00301 {
00302 if ( !hasValidResult() )
00303 {
00304 return false;
00305 }
00306
00307 result.place_pose = cartesian_control_->getPose();
00308 return true;
00309 }
00310
00311 void GripperClickPlaceCartesian::getGripperParams( bool &visible,
00312 Ogre::Vector3 &position,
00313 Ogre::Quaternion &orientation, float &angle )
00314 {
00315 visible = initialized_;
00316 position = camera_node_->convertWorldToLocalPosition( cartesian_control_->getPosition() );
00317 orientation = camera_node_->convertWorldToLocalOrientation( cartesian_control_->getOrientation() );
00318 angle = 0;
00319 }
00320
00321 }