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_pickup_cartesian.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 #include <algorithm>
00044
00045 namespace pr2_gripper_click {
00046
00047 GripperClickPickupCartesian::GripperClickPickupCartesian() :
00048 GripperClickPlugin<GripperClickPickupAction>("Cartesian Control"),
00049 initialized_(false),
00050 gripper_angle_(0)
00051 {
00052 }
00053
00054 void GripperClickPickupCartesian::init( rviz::VisualizationManager *vis_manager, Ogre::SceneManager* scene_manager, 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(false);
00062 cartesian_control_->hide();
00063 }
00064
00065
00066
00067 void GripperClickPickupCartesian::show( )
00068 {
00069 if ( initialized_ )
00070 {
00071 cartesian_control_->show();
00072 }
00073 }
00074
00075 void GripperClickPickupCartesian::hide( )
00076 {
00077 cartesian_control_->hide();
00078 }
00079
00080 bool GripperClickPickupCartesian::setGoal( const GripperClickPickupGoal::ConstPtr &goal )
00081 {
00082 camera_info_ = goal->sensor_data.camera_info;
00083 disparity_image_ = goal->sensor_data.disparity_image;
00084
00085 hide();
00086 initialized_ = false;
00087
00088 gripper_angle_ = 0.541;
00089
00090 setDescription("Please double-click on the desired object to set the initial gripper position.");
00091
00092 return true;
00093 }
00094
00095 void GripperClickPickupCartesian::update(float wall_dt, float ros_dt)
00096 {
00097 cartesian_control_->update();
00098 }
00099
00100 void GripperClickPickupCartesian::onRenderWindowMouseEvents( wxMouseEvent& event, Ogre::Ray &mouse_ray )
00101 {
00102 int x = event.GetX();
00103 int y = event.GetY();
00104
00105 if (event.ButtonDClick(wxMOUSE_BTN_LEFT) && rviz_interaction_tools::hasDisparityValue(disparity_image_, y, x))
00106 {
00107 float px, py, pz;
00108 rviz_interaction_tools::getPoint(disparity_image_, camera_info_, y, x, px, py, pz);
00109
00110 Ogre::Vector3 controls_position(px,py,pz);
00111 controls_position = camera_node_->getPosition() + camera_node_->getOrientation()*controls_position;
00112
00113 Ogre::Quaternion controls_orientation( Ogre::Degree( 225 ), Ogre::Vector3(0,1,0) );
00114 controls_orientation= controls_orientation * Ogre::Quaternion( Ogre::Degree( -90 ), Ogre::Vector3(0,0,1) );
00115
00116
00117
00118 Ogre::Vector3 gripper_position = controls_position - controls_orientation * Ogre::Vector3(0.20,0,0);
00119 Ogre::Quaternion gripper_orientation = controls_orientation;
00120
00121 cartesian_control_->setPosition( gripper_position );
00122 cartesian_control_->setOrientation( gripper_orientation );
00123
00124 cartesian_control_->setControlsPosition( controls_position );
00125 cartesian_control_->setControlsOrientation( controls_orientation );
00126
00127 setDescription("Use the box handles to drag the gripper and the wheels to turn it. You can reset the gripper position\nby double-clicking on the desired location.\n\nUse the mouse wheel to adjust the gripper opening.\n\nPress OK When you are finished.");
00128
00129 initialized_ = true;
00130 show();
00131 }
00132 else
00133 {
00134 if( event.GetWheelRotation() != 0 )
00135 {
00136 gripper_angle_ -= 0.1 * float(event.GetWheelRotation()) / float(event.GetWheelDelta());
00137 if ( gripper_angle_ > 0.541 ) gripper_angle_ = 0.541;
00138 if ( gripper_angle_ < 0 ) gripper_angle_ = 0;
00139 }
00140
00141 if ( event.ButtonDown(wxMOUSE_BTN_LEFT) )
00142 {
00143 cartesian_control_->mouseDown( mouse_ray );
00144 }
00145 if ( event.ButtonUp(wxMOUSE_BTN_LEFT) )
00146 {
00147 cartesian_control_->mouseUp( mouse_ray );
00148 }
00149 else
00150 {
00151 cartesian_control_->mouseMove( mouse_ray );
00152 }
00153 }
00154 }
00155
00156 bool GripperClickPickupCartesian::hasValidResult()
00157 {
00158 return initialized_;
00159 }
00160
00161
00162 bool GripperClickPickupCartesian::getResult(GripperClickPickupResult &result)
00163 {
00164 if ( !hasValidResult() )
00165 {
00166 return false;
00167 }
00168
00169 result.grasp_pose = cartesian_control_->getPose();
00170 result.gripper_opening = gripper_angle_;
00171 return true;
00172 }
00173
00174 void GripperClickPickupCartesian::getGripperParams( bool &visible, Ogre::Vector3 &position, Ogre::Quaternion &orientation, float &angle )
00175 {
00176 visible = initialized_;
00177 position = camera_node_->convertWorldToLocalPosition( cartesian_control_->getPosition() );
00178 orientation = camera_node_->convertWorldToLocalOrientation( cartesian_control_->getOrientation() );
00179 angle = gripper_angle_;
00180 }
00181
00182 }