00001 #ifndef _HELPERS_H_
00002 #define _HELPERS_H_
00003
00004 #include <ros/ros.h>
00005 #include <tf/tf.h>
00006
00007 #include <std_msgs/ColorRGBA.h>
00008
00009 #include <geometry_msgs/Vector3.h>
00010 #include <geometry_msgs/Point.h>
00011 #include <geometry_msgs/Quaternion.h>
00012 #include <geometry_msgs/Pose.h>
00013 #include <geometry_msgs/Transform.h>
00014
00015 #include "pcl/io/pcd_io.h"
00016 #include "pcl/point_types.h"
00017 #include "pcl/filters/passthrough.h"
00018 #include <pcl/features/normal_3d.h>
00019 #include <pcl_ros/transforms.h>
00020
00021 #include <object_manipulator/tools/shape_tools.h>
00022
00023
00024 inline void setMatrixColumns(btMatrix3x3 &mat, btVector3 &X, btVector3 &Y, btVector3 &Z)
00025 {
00026 mat.setValue( X.getX(), Y.getX(), Z.getX(),
00027 X.getY(), Y.getY(), Z.getY(),
00028 X.getZ(), Y.getZ(), Z.getZ() );
00029 }
00030
00034 inline geometry_msgs::PoseStamped generateAlignedPose(const geometry_msgs::PoseStamped original_pose, const tf::Vector3 axis, const tf::Vector3 up)
00035 {
00036 tf::Pose pose_tf;
00037 tf::poseMsgToTF(original_pose.pose, pose_tf);
00038
00039 tf::Point point = pose_tf.getOrigin();
00040
00041 btMatrix3x3 mat;
00042 tf::Vector3 X = axis.normalized();
00043 tf::Vector3 Y = up.cross(axis).normalized();
00044 tf::Vector3 Z = X.cross(Y).normalized();
00045 setMatrixColumns(mat, X, Y, Z);
00046
00047 point -= 0.15*X;
00048
00049 pose_tf = tf::Pose(mat, point);
00050 geometry_msgs::PoseStamped output_pose;
00051 output_pose.header.frame_id = original_pose.header.frame_id;
00052
00053 tf::poseTFToMsg(pose_tf, output_pose.pose);
00054 return output_pose;
00055 }
00056
00060 inline geometry_msgs::PoseStamped generateRelativePose(geometry_msgs::PoseStamped original_pose, double roll, double pitch,
00061 double yaw, double xdist, double ydist, double zdist)
00062 {
00063 tf::Pose pose_tf;
00064 tf::poseMsgToTF(original_pose.pose, pose_tf);
00065 tf::Transform T_rot = tf::Transform(tf::createQuaternionFromRPY(roll, pitch, yaw),
00066 tf::Vector3( xdist, ydist, zdist) );
00067 tf::Transform output_rot = pose_tf * T_rot;
00068 geometry_msgs::PoseStamped output_pose;
00069 output_pose.header.frame_id = original_pose.header.frame_id;
00070 tf::poseTFToMsg(output_rot, output_pose.pose);
00071 return output_pose;
00072 }
00073
00074
00075 template <class PointT>
00076 void box_filter(const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT> &cloud_out, const object_manipulator::shapes::Box &box, bool transform_cloud = false, bool restore_frame = true)
00077 {
00078 pcl::PassThrough<PointT> pass;
00079
00080 cloud_out = cloud_in;
00081 tf::Vector3 center(0,0,0);
00082
00083 if(transform_cloud)
00084 {
00085
00086 pcl_ros::transformPointCloudWithNormals( cloud_out, cloud_out, box.frame.inverse());
00087 }
00088 else {
00089 center = box.frame.getOrigin();
00090 }
00091
00092 if(true)
00093 {
00094 pass.setInputCloud(boost::make_shared<pcl::PointCloud<PointT> >(cloud_out));
00095 pass.setFilterFieldName("z");
00096 pass.setFilterLimits ( center.getZ()-box.dims.getZ()/2, center.getZ()+box.dims.getZ()/2);
00097 pass.setFilterLimitsNegative (false);
00098 pass.filter(cloud_out);
00099 }
00100 if(true)
00101 {
00102 pass.setInputCloud(boost::make_shared<pcl::PointCloud<PointT> >(cloud_out));
00103 pass.setFilterFieldName("x");
00104 pass.setFilterLimits ( center.getX()-box.dims.getX()/2, center.getX()+box.dims.getX()/2);
00105 pass.setFilterLimitsNegative (false);
00106 pass.filter(cloud_out);
00107 }
00108 if(true)
00109 {
00110 pass.setInputCloud(boost::make_shared<pcl::PointCloud<PointT> >(cloud_out));
00111 pass.setFilterFieldName("y");
00112 pass.setFilterLimits ( center.getY()-box.dims.getY()/2, center.getY() + box.dims.getY()/2);
00113 pass.setFilterLimitsNegative (false);
00114 pass.filter(cloud_out);
00115 }
00116
00117 if(transform_cloud && restore_frame) pcl_ros::transformPointCloudWithNormals( cloud_out, cloud_out, box.frame);
00118
00119 }
00120
00121 template <class PointT>
00122 void floating_box_filter(const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT> &cloud_out, const object_manipulator::shapes::Box &box)
00123 {
00124
00125
00126 }
00127
00128
00129
00130
00131
00132 #endif