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_interactive_manipulation/cartesian_gripper_control_tool.h"
00031
00032 #include "rviz/visualization_manager.h"
00033 #include "rviz/properties/property_manager.h"
00034 #include "rviz/properties/property.h"
00035 #include "rviz/viewport_mouse_event.h"
00036 #include "rviz/render_panel.h"
00037 #include "rviz/view_controller.h"
00038 #include "rviz/tf_frame_property.h"
00039 #include "rviz/viewport_mouse_event.h"
00040
00041 #include <OGRE/OgreRay.h>
00042 #include <OGRE/OgrePlane.h>
00043 #include <OGRE/OgreCamera.h>
00044 #include <OGRE/OgreSceneNode.h>
00045 #include <OGRE/OgreViewport.h>
00046
00047 #include <tf/transform_listener.h>
00048
00049 #include <wx/event.h>
00050
00051 namespace pr2_interactive_manipulation
00052 {
00053
00054 CartesianGripperControlTool::CartesianGripperControlTool( const std::string& name, char shortcut_key,
00055 rviz::VisualizationManager* manager ) : rviz::Tool( name, shortcut_key, manager ),
00056 left_control_( "left_arm", "l_wrist_roll_link", "base_link", manager ),
00057 right_control_( "right_arm", "r_wrist_roll_link", "base_link", manager ),
00058 active_control_(&left_control_),
00059 status_(IDLE)
00060 {
00061 deactivate();
00062 setUseRobotCoords( false );
00063 }
00064
00065 CartesianGripperControlTool::~CartesianGripperControlTool()
00066 {
00067 }
00068
00069 void CartesianGripperControlTool::activate()
00070 {
00071 left_control_.show();
00072 right_control_.show();
00073 left_control_.reset();
00074 right_control_.reset();
00075 }
00076
00077
00078 void CartesianGripperControlTool::deactivate()
00079 {
00080 left_control_.hide();
00081 right_control_.hide();
00082 }
00083
00084 void CartesianGripperControlTool::update(float wall_dt, float ros_dt)
00085 {
00086 left_control_.update();
00087 right_control_.update();
00088 }
00089
00090
00091 int CartesianGripperControlTool::processMouseEvent( rviz::ViewportMouseEvent& event )
00092 {
00093 int width = event.viewport->getActualWidth();
00094 int height = event.viewport->getActualHeight();
00095
00096 Ogre::Ray mouse_ray = event.viewport->getCamera()->getCameraToViewportRay(
00097 (float)event.event.GetX() / (float)width, (float)event.event.GetY() / (float)height );
00098
00099 float left_dist = left_control_.getClosestIntersection( mouse_ray );
00100 float right_dist = right_control_.getClosestIntersection( mouse_ray );
00101
00102 bool above_control = ( left_dist != CartesianGripperControl::NO_INTERSECTION || right_dist != CartesianGripperControl::NO_INTERSECTION );
00103
00104 switch ( status_ )
00105 {
00106 case IDLE:
00107 {
00108 if ( event.event.LeftDown() && above_control )
00109 {
00110 active_control_ = left_dist < right_dist ? &left_control_ : &right_control_;
00111 active_control_->mouseDown(mouse_ray);
00112 status_=CONTROL;
00113 }
00114 else if (event.panel->getViewController())
00115 {
00116 event.panel->getViewController()->handleMouseEvent(event);
00117 }
00118 break;
00119 }
00120
00121 case CONTROL:
00122 {
00123 if ( event.event.LeftUp() )
00124 {
00125 active_control_->mouseUp(mouse_ray);
00126 status_ = IDLE;
00127 }
00128 else
00129 {
00130 active_control_->mouseMove(mouse_ray);
00131 }
00132 break;
00133 }
00134 }
00135
00136 return 0;
00137 }
00138
00139 void CartesianGripperControlTool::enumerateProperties(rviz::PropertyManager* property_manager, const rviz::CategoryPropertyWPtr& parent)
00140 {
00141 use_robot_coords_property_ = property_manager->createProperty<rviz::BoolProperty>(
00142 "Use robot frame", "Tool " + getName(),
00143 boost::bind( &CartesianGripperControlTool::getUseRobotCoords, this ),
00144 boost::bind( &CartesianGripperControlTool::setUseRobotCoords, this, _1 ),
00145 parent, this );
00146 }
00147
00148 void CartesianGripperControlTool::setUseRobotCoords( bool use )
00149 {
00150 use_robot_coords_ = use;
00151 left_control_.setUseReferenceFrame(use);
00152 right_control_.setUseReferenceFrame(use);
00153 }
00154
00155 }
00156