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/point_tools.h"
00031
00032 #include <rviz/properties/string_property.h>
00033
00034 #include <pcl_ros/point_cloud.h>
00035 #include <pcl/features/integral_image_normal.h>
00036
00037 #include <geometry_msgs/Point.h>
00038 #include <geometry_msgs/PoseStamped.h>
00039 #include <OGRE/OgreVector3.h>
00040 #include <OGRE/OgreViewport.h>
00041 #include <OGRE/OgreCamera.h>
00042 #include <rviz/display_context.h>
00043 #include <rviz/selection/selection_manager.h>
00044 #include <rviz/properties/int_property.h>
00045 #include <tf/transform_datatypes.h>
00046 #include <visualization_msgs/Marker.h>
00047
00048
00049
00050
00051
00052 namespace pr2_interactive_manipulation
00053 {
00054
00055 LookAtTool::LookAtTool()
00056 {
00057 topic_property_->setStdString("/rviz/look_here");
00058 };
00059
00060 SetGripperTool::SetGripperTool()
00061 {
00062 createProperties();
00063 topic_property_->setStdString("/rviz/set_gripper_point");
00064 topic_property_pose_->setStdString("/cloud_click_point");
00065 pub_pose_ = nh_.advertise<geometry_msgs::PoseStamped>( topic_property_pose_->getStdString(), 1 );
00066 };
00067
00068 void SetGripperTool::createProperties()
00069 {
00070 topic_property_pose_ = new rviz::StringProperty("Pose Topic",
00071 "/cloud_click_point", "Topic on which to publish poses.",
00072 getPropertyContainer(),
00073 SLOT( updatePoseTopic() ), this);
00074
00075
00076 normal_box_padding_ = new rviz::IntProperty("Normal box padding",
00077 7,
00078 "Size of box around clicked point to sample for normal");
00079
00080
00081 far_clip_distance_ = new rviz::FloatProperty("Far Clip Distance",
00082 50.0,
00083 "Maximum distance of depth selection");
00084
00085
00086 }
00087
00088 void SetGripperTool::updatePoseTopic()
00089 {
00090 pub_pose_ = nh_.advertise<geometry_msgs::PoseStamped>( topic_property_pose_->getStdString(), 1 );
00091 }
00092
00093
00094
00095
00096 int SetGripperTool::processMouseEvent( rviz::ViewportMouseEvent& event )
00097 {
00098 int flags = 0;
00099 Ogre::Vector3 pos;
00100
00101
00102 bool success = context_->getSelectionManager()->get3DPoint( event.viewport, event.x, event.y, pos );
00103 setCursor( success ? hit_cursor_ : std_cursor_ );
00104
00105
00106 if ( success )
00107 {
00108 std::ostringstream s;
00109 s << "<b>Left-Click:</b> Select this point.";
00110 s.precision(3);
00111 s << " [" << pos.x << "," << pos.y << "," << pos.z << "]";
00112 setStatus( s.str().c_str() );
00113
00114
00115 if( event.leftUp() )
00116 {
00117 tf::Vector3 normal_vec(0,1,0);
00118
00119
00120 float starting_max_depth = event.viewport->getCamera()->getFarClipDistance();
00121 event.viewport->getCamera()->setFarClipDistance(far_clip_distance_->getFloat());
00122
00123
00124 int bp = normal_box_padding_->getInt();
00125 unsigned int box_width(2*bp+1);
00126
00127
00128 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>(box_width, box_width));
00129 cloud->reserve(box_width * box_width);
00130
00131
00132 std::vector<Ogre::Vector3> box_pos;
00133 bool success_box = context_->getSelectionManager()->get3DPatch(event.viewport, event.x - bp, event.y - bp, box_width, box_width, true, box_pos);
00134
00135
00136 for (unsigned int i = 0; i < box_pos.size(); ++ i)
00137 {
00138 (*cloud)[i] = pcl::PointXYZ(box_pos[i].x, box_pos[i].y, box_pos[i].z);
00139 }
00140
00141
00142
00143 if(box_pos.size() > 3)
00144 {
00145 pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
00146
00147 Ogre::Vector3 camera_pos = event.viewport->getCamera()->getDerivedPosition();
00148
00149 ne.setViewPoint(camera_pos.x, camera_pos.y, camera_pos.z);
00150 ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
00151 ne.setMaxDepthChangeFactor(0.02f);
00152 ne.setNormalSmoothingSize(10.0f);
00153 ne.setRectSize(bp - 1, bp -1);
00154 ne.setInputCloud(cloud);
00155
00156
00157 unsigned center_point_index = bp + ( box_width ) * bp;
00158 pcl::Normal normal_point;
00159 ne.computePointNormal(bp, bp, center_point_index, normal_point);
00160
00161
00162 if (!std::isnan(normal_point.normal_x)){
00163
00164 tf::Vector3 point_to_head(tf::Vector3(camera_pos.x - pos.x, camera_pos.y - pos.y, camera_pos.z - pos.z).normalized());
00165
00166 normal_vec = tf::Vector3(normal_point.normal_x, normal_point.normal_y, normal_point.normal_z);
00167
00168
00169 if(point_to_head.dot(normal_vec) < 0)
00170 normal_vec *= -1;
00171 }
00172 else
00173 {
00174 ROS_WARN("Failed to find normal - using default %f %f %f", normal_vec.x(), normal_vec.y(), normal_vec.z());
00175 }
00176 }
00177
00178
00179
00180 geometry_msgs::PoseStamped ps;
00181
00182 ps.pose.position.x = pos.x;
00183 ps.pose.position.y = pos.y;
00184 ps.pose.position.z = pos.z;
00185 ps.header.frame_id = context_->getFixedFrame().toStdString();
00186 ps.header.stamp = ros::Time::now();
00187
00188 tf::Vector3 Z = normal_vec.normalized();
00189 tf::Vector3 Y = normal_vec.cross(tf::Vector3(0,0,1)).normalized();
00190 tf::Vector3 X = Y.cross(normal_vec).normalized();
00191 tf::Matrix3x3 mat(X.x(), Y.x(), Z.x(),
00192 X.y(), Y.y(), Z.y(),
00193 X.z(), Y.z(), Z.z());
00194 tf::Quaternion q;
00195 mat.getRotation(q);
00196 tf::quaternionTFToMsg(q, ps.pose.orientation);
00197
00198 pub_pose_.publish( ps );
00199
00200 if ( auto_deactivate_property_->getBool() )
00201 {
00202 flags |= Finished;
00203 }
00204
00205
00206 event.viewport->getCamera()->setFarClipDistance(starting_max_depth);
00207 }
00208
00209 }
00210 else
00211 {
00212 setStatus( "Move over an object to select the target point." );
00213 }
00214
00215
00216 return flags;
00217
00218 }
00219
00220 NavigateToTool::NavigateToTool()
00221 {
00222 topic_property_->setStdString("/rviz/navigate_to");
00223 };
00224
00225 }
00226
00227 #include <pluginlib/class_list_macros.h>
00228 PLUGINLIB_EXPORT_CLASS( pr2_interactive_manipulation::LookAtTool, rviz::Tool )
00229 PLUGINLIB_EXPORT_CLASS( pr2_interactive_manipulation::SetGripperTool, rviz::Tool )
00230 PLUGINLIB_EXPORT_CLASS( pr2_interactive_manipulation::NavigateToTool, rviz::Tool )