38 #include <geometry_msgs/PoseArray.h> 39 #include <geometry_msgs/PoseStamped.h> 47 ConnectionBasedNodelet::onInit();
53 pub_ = advertise<geometry_msgs::PoseArray>(*
pnh_,
"output", 1);
54 pub_best_ = advertise<geometry_msgs::PoseStamped>(*
pnh_,
"output_best", 1);
55 pub_selected_ = advertise<geometry_msgs::PoseStamped>(*
pnh_,
"output_selected", 1);
68 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
81 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
84 std::vector<double> dimensions;
85 dimensions.push_back(box_msg->dimensions.x);
86 dimensions.push_back(box_msg->dimensions.y);
87 dimensions.push_back(box_msg->dimensions.z);
88 size_t longest_index = 0;
89 for (
size_t i = 1; i < 3; i++) {
90 if (dimensions[i] > dimensions[longest_index]) {
97 if (longest_index == 2) {
106 if (longest_index == 0) {
128 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
129 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
146 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
147 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
149 geometry_msgs::PoseArray pose_array;
150 geometry_msgs::PoseArray prepose_array;
151 pose_array.header = box_msg->header;
152 prepose_array.header = box_msg->header;
153 Eigen::Affine3d center;
155 Eigen::Vector3d
z = center.rotation().col(2);
156 Plane p(Eigen::Vector3f(z[0], z[1], z[2]), 0);
157 Eigen::Vector3d ray = center.translation().normalized();
158 Eigen::Vector3d ray_projected;
160 ray_projected.normalize();
162 Eigen::Matrix3d center_refined_mat;
163 center_refined_mat.col(0) = ray_projected;
164 center_refined_mat.col(2) =
z;
165 center_refined_mat.col(1) = z.cross(ray_projected);
166 Eigen::Affine3d center_refined
167 = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(center_refined_mat);
169 const double angle_margin = 0.2;
170 const double start_angle =
M_PI / 2.0 + angle_margin;
171 const double end_angle =
M_PI +
M_PI / 2.0 - angle_margin;
173 const double theta = (end_angle - start_angle) / angle_divide_num_ * i + start_angle;
174 Eigen::Vector3d offset_vec = Eigen::Vector3d(
cos(theta),
sin(theta), 0);
175 Eigen::Vector3d pre_approach_pos
177 Eigen::Matrix3d orientation;
178 Eigen::Vector3d x_vec
179 = (center_refined.translation() - pre_approach_pos).
normalized();
180 Eigen::Vector3d y_vec = z.cross(x_vec);
182 orientation.col(0) = x_vec;
183 orientation.col(1) = y_vec;
184 orientation.col(2) =
z;
186 Eigen::Affine3d pre_grasp_pose = Eigen::Translation3d(pre_approach_pos) * Eigen::Quaterniond(orientation);
187 Eigen::Affine3d grasp_pose = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(orientation);
188 geometry_msgs::Pose ros_prepose;
189 geometry_msgs::Pose ros_pose;
192 prepose_array.poses.push_back(ros_prepose);
193 pose_array.poses.push_back(ros_pose);
197 geometry_msgs::PoseStamped best;
198 best.header = pose_array.header;
199 best.pose = pose_array.poses[pose_array.poses.size() / 2];
202 output_buf.push_front(boost::make_tuple(pose_array, prepose_array));
206 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
207 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg,
210 geometry_msgs::PoseArray pose_array;
211 geometry_msgs::PoseArray prepose_array;
212 pose_array.header = box_msg->header;
213 prepose_array.header = box_msg->header;
215 Eigen::Affine3d center;
217 const double angle_margin = 0.2;
218 const double start_angle = angle_margin;
219 const double end_angle =
M_PI - angle_margin;
224 Eigen::Vector3d offset_vec;
226 offset_vec = Eigen::Vector3d(
sin(theta), 0,
cos(theta));
229 offset_vec = Eigen::Vector3d(0,
cos(theta),
sin(theta));
231 Eigen::Vector3d pre_approach_pos
234 Eigen::Matrix3d orientation;
236 Eigen::Vector3d x_vec
237 = (center.translation() - pre_approach_pos).
normalized();
238 Eigen::Vector3d z_vec = center.rotation().col(1);
239 Eigen::Vector3d y_vec = z_vec.cross(x_vec);
240 orientation.col(0) = x_vec;
241 orientation.col(1) = y_vec;
242 orientation.col(2) = z_vec;
245 Eigen::Vector3d x_vec = (center.translation() - pre_approach_pos).
normalized();
246 Eigen::Vector3d z_vec = center.rotation().col(0);
247 Eigen::Vector3d y_vec = z_vec.cross(x_vec);
248 orientation.col(0) = x_vec;
249 orientation.col(1) = y_vec;
250 orientation.col(2) = z_vec;
253 Eigen::Affine3d pre_grasp_pose = Eigen::Translation3d(pre_approach_pos) * Eigen::Quaterniond(orientation);
254 Eigen::Affine3d grasp_pose = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(orientation);
255 geometry_msgs::Pose ros_prepose, ros_pose;
258 pose_array.poses.push_back(ros_pose);
259 prepose_array.poses.push_back(ros_prepose);
263 geometry_msgs::PoseStamped best;
264 best.header = pose_array.header;
265 best.pose = pose_array.poses[pose_array.poses.size() / 2];
268 output_buf.push_front(boost::make_tuple(pose_array, prepose_array));
272 boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> >::iterator it =
output_buf.begin();
274 geometry_msgs::PoseArray pose_array = it->get<0>();
275 geometry_msgs::PoseArray prepose_array = it->get<1>();
277 if(pose_array.header.stamp == index->header.stamp){
278 geometry_msgs::PoseStamped ps;
279 ps.header = pose_array.header;
280 ps.pose = pose_array.poses[index->data];
283 ps.header = prepose_array.header;
284 ps.pose = prepose_array.poses[index->data];
boost::circular_buffer< boost::tuple< geometry_msgs::PoseArray, geometry_msgs::PoseArray > > output_buf
#define NODELET_INFO_STREAM(...)
ros::Publisher pub_preapproach_
#define NODELET_ERROR(...)
virtual void selectedIndexCallback(const jsk_recognition_msgs::Int32StampedConstPtr &index)
void publish(const boost::shared_ptr< M > &message) const
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::HandleEstimator, nodelet::Nodelet)
virtual void unsubscribe()
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
virtual void handleSmallEnoughStandOnPlane(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
TFSIMD_FORCE_INLINE Vector3 normalized() const
virtual void handleSmallEnoughLieOnPlane(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg, bool y_longest)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
ros::Publisher pub_selected_preapproach_
ros::Subscriber sub_index_
virtual void project(const Eigen::Vector3f &p, Eigen::Vector3f &output)
ros::Publisher pub_selected_
virtual void estimateHandle(const HandleType &handle_type, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_