#include <ros/ros.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <boost/bind.hpp>
#include <std_msgs/String.h>
#include <sensor_msgs/point_cloud_conversion.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <object_manipulation_msgs/GraspPlanning.h>
#include <object_manipulation_msgs/ManipulationResult.h>
#include <object_manipulation_msgs/FindClusterBoundingBox.h>
#include <object_manipulator/tools/service_action_wrappers.h>
#include <dynamic_reconfigure/server.h>
#include "pr2_grasp_adjust/EstimateConfig.h"
#include <object_manipulation_msgs/GraspPlanningAction.h>
#include <actionlib/server/simple_action_server.h>
#include <iostream>
#include <fstream>
#include <queue>
#include "gripper_model.h"
#include "helpers.h"
#include "grasp_adjust.h"
#include "pcl/io/pcd_io.h"
#include "pcl/point_types.h"
#include <pcl/ModelCoefficients.h>
#include <pcl/features/normal_3d.h>
#include <pcl/features/normal_3d_omp.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/filters/passthrough.h>
#include "pcl/filters/voxel_grid.h"
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
Go to the source code of this file.
Classes | |
class | GraspAdjustActionServer |
Typedefs | |
typedef pcl::PointXYZRGBNormal | PointT |
Finds optimal grasps near a provided grasp pose. | |
Functions | |
int | main (int argc, char *argv[]) |
Variables | |
const int | GLOBAL_SEARCH = pr2_grasp_adjust::Estimate_global_search |
const int | LOCAL_SEARCH = pr2_grasp_adjust::Estimate_local_search |
std::ofstream | outputFile |
const int | SINGLE_POSE = pr2_grasp_adjust::Estimate_single_pose |
typedef pcl::PointXYZRGBNormal PointT |
Finds optimal grasps near a provided grasp pose.
Definition at line 95 of file grasp_adjust_action_server.cpp.
int main | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 457 of file grasp_adjust_action_server.cpp.
const int GLOBAL_SEARCH = pr2_grasp_adjust::Estimate_global_search |
Definition at line 97 of file grasp_adjust_action_server.cpp.
const int LOCAL_SEARCH = pr2_grasp_adjust::Estimate_local_search |
Definition at line 98 of file grasp_adjust_action_server.cpp.
std::ofstream outputFile |
Definition at line 102 of file grasp_adjust_action_server.cpp.
const int SINGLE_POSE = pr2_grasp_adjust::Estimate_single_pose |
Definition at line 99 of file grasp_adjust_action_server.cpp.