#include <object_manipulation_tools/manipulation_utils/Utilities.h>
#include <pcl/ros/conversions.h>
#include <pcl/common/centroid.h>
Go to the source code of this file.
Namespaces | |
namespace | manipulation_utils |
Functions | |
void | manipulation_utils::createBoundingSphereCollisionModel (const sensor_msgs::PointCloud cluster, double radius, arm_navigation_msgs::CollisionObject &obj) |
void | manipulation_utils::generateCandidateGrasps (const object_manipulation_msgs::Grasp firstGrasp, tf::Vector3 rotationAxis, int numCandidates, std::vector< object_manipulation_msgs::Grasp > &graspCandidates) |
void | manipulation_utils::generateGraspPoses (const geometry_msgs::Pose &pose, tf::Vector3 rotationAxis, int numCandidates, std::vector< geometry_msgs::Pose > &poses) |
void | manipulation_utils::rectifyPoseZDirection (const geometry_msgs::Pose &actual_pose, const geometry_msgs::Pose &rectification_pose, geometry_msgs::Pose &rectified_pose) |