36 #define BOOST_PARAMETER_MAX_ARITY 7 39 #include <pcl/features/normal_3d.h> 40 #include <pcl/kdtree/kdtree_flann.h> 41 #include <pcl/common/transforms.h> 42 #include <pcl/filters/passthrough.h> 50 inline float NORM(
float vx,
float vy,
float vz){
return sqrt(vx*vx+vy*vy+vz*vz);}
54 void HintedHandleEstimator::onInit()
56 DiagnosticNodelet::onInit();
57 pub_pose_ = advertise<geometry_msgs::PoseStamped>(
58 *pnh_,
"handle_pose", 1);
59 pub_length_ = advertise<std_msgs::Float64>(
60 *pnh_,
"handle_length", 1);
61 pub_handle_ = advertise<jsk_recognition_msgs::SimpleHandle>(
63 pub_debug_marker_ = advertise<visualization_msgs::Marker>(*pnh_,
"debug_marker", 1);
64 pub_debug_marker_array_ = advertise<visualization_msgs::MarkerArray>(*pnh_,
"debug_marker_array", 1);
66 pnh_->param(
"finger_l", handle.finger_l, 0.03);
67 pnh_->param(
"finger_d", handle.finger_d, 0.02);
68 pnh_->param(
"finger_w", handle.finger_w, 0.01);
69 pnh_->param(
"arm_l", handle.arm_l, 0.05);
70 pnh_->param(
"arm_d", handle.arm_d, 0.02);
71 pnh_->param(
"arm_w", handle.arm_w, 0.1);
75 void HintedHandleEstimator::subscribe()
77 sub_cloud_.subscribe(*pnh_,
"cloud", 1);
78 sub_point_.subscribe(*pnh_,
"point", 1);
79 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
80 sync_->connectInput(sub_cloud_, sub_point_);
81 sync_->registerCallback(boost::bind(&HintedHandleEstimator::estimate,
this, _1, _2));
84 void HintedHandleEstimator::unsubscribe()
86 sub_cloud_.unsubscribe();
87 sub_point_.unsubscribe();
90 void HintedHandleEstimator::estimate(
91 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
92 const geometry_msgs::PointStampedConstPtr &point_msg)
95 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
96 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals(
new pcl::PointCloud<pcl::Normal>);
97 pcl::PassThrough<pcl::PointXYZ> pass;
99 std::vector<int> pointIdxNKNSearch(K);
100 std::vector<float> pointNKNSquaredDistance(K);
101 pcl::search::KdTree<pcl::PointXYZ>::Ptr kd_tree(
new pcl::search::KdTree<pcl::PointXYZ>);
104 geometry_msgs::PointStamped transed_point;
108 listener_.waitForTransform(cloud->header.frame_id, point_msg->header.frame_id, now,
ros::Duration(1.0));
109 listener_.transformPoint(cloud->header.frame_id, now, *point_msg, point_msg->header.frame_id, transed_point);
116 pcl::PointXYZ searchPoint;
117 searchPoint.x = transed_point.point.x;
118 searchPoint.y = transed_point.point.y;
119 searchPoint.z = transed_point.point.z;
122 pass.setInputCloud(cloud);
123 pass.setFilterFieldName(
"x");
124 pass.setFilterLimits(searchPoint.x - 3*handle.arm_w, searchPoint.x + 3*handle.arm_w);
126 pass.setInputCloud(cloud);
127 pass.setFilterFieldName(
"y");
128 pass.setFilterLimits(searchPoint.y - 3*handle.arm_w, searchPoint.y + 3*handle.arm_w);
130 pass.setInputCloud(cloud);
131 pass.setFilterFieldName(
"z");
132 pass.setFilterLimits(searchPoint.z - 3*handle.arm_w, searchPoint.z + 3*handle.arm_w);
135 if(cloud->points.size() < 10){
140 pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
141 ne.setInputCloud(cloud);
142 ne.setSearchMethod(kd_tree);
143 ne.setRadiusSearch(0.02);
144 ne.setViewPoint(0, 0, 0);
145 ne.compute(*cloud_normals);
150 if(! (kd_tree->nearestKSearch (searchPoint, K, pointIdxNKNSearch, pointNKNSquaredDistance) > 0)){
154 float x = cloud->points[pointIdxNKNSearch[0]].x;
155 float y = cloud->points[pointIdxNKNSearch[0]].y;
156 float z = cloud->points[pointIdxNKNSearch[0]].z;
157 float v_x = cloud_normals->points[pointIdxNKNSearch[0]].normal_x;
158 float v_y = cloud_normals->points[pointIdxNKNSearch[0]].normal_y;
159 float v_z = cloud_normals->points[pointIdxNKNSearch[0]].normal_z;
164 double min_theta_index = 0;
165 double min_width = 100;
167 visualization_msgs::Marker debug_hand_marker;
168 debug_hand_marker.header = cloud_msg->header;
169 debug_hand_marker.ns =
string(
"debug_grasp");
170 debug_hand_marker.id = 0;
171 debug_hand_marker.type = visualization_msgs::Marker::LINE_LIST;
172 debug_hand_marker.pose.orientation.w = 1;
173 debug_hand_marker.scale.x=0.003;
176 for(
double theta_=0; theta_<3.14/2;
181 geometry_msgs::Pose pose_respected_to_tf;
182 pose_respected_to_tf.position.x =
x;
183 pose_respected_to_tf.position.y =
y;
184 pose_respected_to_tf.position.z =
z;
185 pose_respected_to_tf.orientation.x = temp_qua.getX();
186 pose_respected_to_tf.orientation.y = temp_qua.getY();
187 pose_respected_to_tf.orientation.z = temp_qua.getZ();
188 pose_respected_to_tf.orientation.w = temp_qua.
getW();
189 Eigen::Affine3d box_pose_respected_to_cloud_eigend;
191 Eigen::Affine3d box_pose_respected_to_cloud_eigend_inversed
192 = box_pose_respected_to_cloud_eigend.inverse();
193 Eigen::Matrix4f box_pose_respected_to_cloud_eigen_inversed_matrixf;
194 Eigen::Matrix4d box_pose_respected_to_cloud_eigen_inversed_matrixd
195 = box_pose_respected_to_cloud_eigend_inversed.matrix();
196 jsk_recognition_utils::convertMatrix4<Eigen::Matrix4d, Eigen::Matrix4f>(
197 box_pose_respected_to_cloud_eigen_inversed_matrixd,
198 box_pose_respected_to_cloud_eigen_inversed_matrixf);
199 Eigen::Affine3f offset = Eigen::Affine3f(box_pose_respected_to_cloud_eigen_inversed_matrixf);
200 pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(
new pcl::PointCloud<pcl::PointXYZ>);
201 pcl::transformPointCloud(*cloud, *output_cloud, offset);
203 pcl::PassThrough<pcl::PointXYZ> pass;
204 pcl::PointCloud<pcl::PointXYZ>::Ptr points_z(
new pcl::PointCloud<pcl::PointXYZ>), points_yz(
new pcl::PointCloud<pcl::PointXYZ>), points_xyz(
new pcl::PointCloud<pcl::PointXYZ>);
205 pass.setInputCloud(output_cloud);
206 pass.setFilterFieldName(
"y");
207 pass.setFilterLimits(-handle.arm_w*2, handle.arm_w*2);
208 pass.filter(*points_z);
209 pass.setInputCloud(points_z);
210 pass.setFilterFieldName(
"z");
211 pass.setFilterLimits(-handle.finger_d, handle.finger_d);
212 pass.filter(*points_yz);
213 pass.setInputCloud(points_yz);
214 pass.setFilterFieldName(
"x");
215 pass.setFilterLimits(-(handle.arm_l-handle.finger_l), handle.finger_l);
216 pass.filter(*points_xyz);
217 pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
219 points_xyz->points[
index].x = points_xyz->points[
index].z = 0;
221 if(points_xyz->points.size() == 0){
ROS_INFO(
"points are empty");
return;}
222 kdtree.setInputCloud(points_xyz);
223 std::vector<int> pointIdxRadiusSearch;
224 std::vector<float> pointRadiusSquaredDistance;
225 pcl::PointXYZ search_point_tree;
226 search_point_tree.x=search_point_tree.y=search_point_tree.z=0;
227 if( kdtree.radiusSearch(search_point_tree, 10, pointIdxRadiusSearch, pointRadiusSquaredDistance) > 0 ){
228 double before_w=10, temp_w;
230 temp_w =
sqrt(pointRadiusSquaredDistance[
index]);
231 if(temp_w - before_w > handle.finger_w*2){
236 if(before_w < min_width){
237 min_theta_index = theta_;
238 min_width = before_w;
243 geometry_msgs::Point temp_point;
244 std_msgs::ColorRGBA temp_color;
245 temp_color.r=0; temp_color.g=0; temp_color.b=1; temp_color.a=1;
246 temp_point.x=x-temp_mat.
getColumn(1)[0] * before_w;
247 temp_point.
y=y-temp_mat.
getColumn(1)[1] * before_w;
248 temp_point.
z=z-temp_mat.
getColumn(1)[2] * before_w;
249 debug_hand_marker.points.push_back(temp_point);
250 debug_hand_marker.colors.push_back(temp_color);
251 temp_point.
x+=2*temp_mat.
getColumn(1)[0] * before_w;
252 temp_point.
y+=2*temp_mat.
getColumn(1)[1] * before_w;
253 temp_point.
z+=2*temp_mat.
getColumn(1)[2] * before_w;
254 debug_hand_marker.points.push_back(temp_point);
255 debug_hand_marker.colors.push_back(temp_color);
258 geometry_msgs::PoseStamped handle_pose_stamped;
259 handle_pose_stamped.header = cloud_msg->header;
260 handle_pose_stamped.pose.position.
x =
x;
261 handle_pose_stamped.pose.position.y =
y;
262 handle_pose_stamped.pose.position.z =
z;
263 handle_pose_stamped.pose.orientation.x = min_qua.getX();
264 handle_pose_stamped.pose.orientation.y = min_qua.getY();
265 handle_pose_stamped.pose.orientation.z = min_qua.getZ();
266 handle_pose_stamped.pose.orientation.w = min_qua.
getW();
267 std_msgs::Float64 min_width_msg;
268 min_width_msg.data = min_width;
270 pub_debug_marker_.publish(debug_hand_marker);
272 jsk_recognition_msgs::SimpleHandle simple_handle;
273 simple_handle.header = handle_pose_stamped.header;
274 simple_handle.pose = handle_pose_stamped.pose;
275 simple_handle.handle_width = min_width;
276 pub_handle_.publish(simple_handle);
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::HintedHandleEstimator, nodelet::Nodelet)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
TFSIMD_FORCE_INLINE const tfScalar & getW() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
visualization_msgs::MarkerArray make_handle_array(geometry_msgs::PoseStamped pose, handle_model handle)
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
float NORM(float vx, float vy, float vz)
TFSIMD_FORCE_INLINE Vector3 getColumn(int i) const