Utilities.h
Go to the documentation of this file.
00001 
00002 #ifndef MANIPULATION_UTILS_H_
00003 #define MANIPULATION_UTILS_H_
00004 #include <ros/ros.h>
00005 #include <sensor_msgs/PointCloud.h>
00006 #include <sensor_msgs/PointCloud2.h>
00007 #include <sensor_msgs/point_cloud_conversion.h>
00008 #include <geometry_msgs/Pose.h>
00009 #include <tf/tf.h>
00010 #include <pcl/point_cloud.h>
00011 #include <pcl/point_types.h>
00012 #include <object_manipulation_msgs/Grasp.h>
00013 #include <arm_navigation_msgs/CollisionObject.h>
00014 
00015 namespace manipulation_utils
00016 {
00017         void generateGraspPoses(const geometry_msgs::Pose &pose,tf::Vector3 rotationAxis,int numCandidates,
00018                         std::vector<geometry_msgs::Pose> &poses);
00019 
00020         /*
00021          * Generates additional grasps by rotating original grasp about the rotational axis 'numCandidate' times
00022          */
00023         void generateCandidateGrasps(const object_manipulation_msgs::Grasp firstGrasp,tf::Vector3 rotationAxis,int numCandidates,
00024                         std::vector<object_manipulation_msgs::Grasp> &graspCandidates);
00025 
00026         void createBoundingSphereCollisionModel(const sensor_msgs::PointCloud cluster,double radius,
00027                         arm_navigation_msgs::CollisionObject &obj);
00028 
00029         // post multiplies a rotation to actual_pose such that the z vector points in the direction of that in
00030         // rectification_pose.  No translation is produced.
00031         void rectifyPoseZDirection(const geometry_msgs::Pose &actual_pose,
00032                         const geometry_msgs::Pose &rectification_pose,geometry_msgs::Pose &rectified_pose);
00033         void rectifyPoseZDirection(const geometry_msgs::Pose &actual_pose,
00034                         const tf::Transform &rectification_tf,geometry_msgs::Pose &rectified_pose);
00035 }
00036 
00037 #endif


object_manipulation_tools
Author(s): Jnicho
autogenerated on Mon Oct 6 2014 00:56:17