Classes | Public Types | Public Member Functions | Public Attributes | Private Member Functions
GraspAdjust Class Reference

A class for finding grasp poses. More...

#include <grasp_adjust.h>

List of all members.

Classes

struct  params

Public Types

typedef
pr2_grasp_adjust::EstimateConfig 
Config
typedef
pr2_grasp_adjust::DebugConfig 
Debug

Public Member Functions

int findGrasps (const geometry_msgs::PoseStamped &grasp_pose_in, std::vector< geometry_msgs::PoseStamped > *adjusted_poses, std::vector< double > *pose_scores, int search_mode=0, std::string common_frame=std::string("base_footprint"))
 The function that performs the whole grasp adjustment.
int findGrasps (const geometry_msgs::PoseStamped &grasp_pose_in, std::priority_queue< GripperModel, std::vector< GripperModel >, GripperModel::compareModels > *ranked_poses, int search_mode=0, std::string common_frame=std::string("base_footprint"))
 The function that performs the whole grasp adjustment.
 GraspAdjust ()
void setInputCloud (const pcl::PointCloud< PointT > &cloud)
 The function that performs the whole grasp adjustment.

Public Attributes

tf::TransformBroadcasterbroadcaster_
tf::Vector3 centroid_
pcl::PointCloud< PointTcloud_in_
pcl::PointCloud< PointTcloud_out_
pcl::PointCloud< PointTcloud_process_
Config config_
Debug debug_
const GripperModel DEFAULT_GRIPPER
bool got_first_cloud_
pcl::PointCloud< PointTlast_cloud_
tf::TransformListenerlistener_
ros::NodeHandle nh_
ros::NodeHandle nh_pvt_
ros::Time now_
ros::Publisherpub_cloud_
ros::Publisherpub_cloud_roi_
ros::Publisherpub_marker_
ros::Publisherpub_marker_array_
GripperModel starting_gripper_
std::ofstream train_file_
bool training_
FeatureWeights weights_

Private Member Functions

bool doGradientDescent (GripperModel &seed, int steps)
 Performs a gradient descent for a presecribed number of steps, returns true if it ended on a local minimum.

Detailed Description

A class for finding grasp poses.

This description is displayed lower in the doxygen as an extended description along with the above brief description.

Definition at line 82 of file grasp_adjust.h.


Member Typedef Documentation

typedef pr2_grasp_adjust::EstimateConfig GraspAdjust::Config

Definition at line 105 of file grasp_adjust.h.

typedef pr2_grasp_adjust::DebugConfig GraspAdjust::Debug

Definition at line 108 of file grasp_adjust.h.


Constructor & Destructor Documentation

Definition at line 87 of file grasp_adjust.cpp.


Member Function Documentation

bool GraspAdjust::doGradientDescent ( GripperModel seed,
int  steps 
) [private]

Performs a gradient descent for a presecribed number of steps, returns true if it ended on a local minimum.

This description is displayed lower in the doxygen as an extended description along with the above brief description.

Parameters:
seedThe gripper model starting position for the descent.
stepsThe number of steps to use.

Definition at line 124 of file grasp_adjust.cpp.

int GraspAdjust::findGrasps ( const geometry_msgs::PoseStamped &  grasp_pose_in,
std::vector< geometry_msgs::PoseStamped > *  adjusted_poses,
std::vector< double > *  pose_scores,
int  search_mode = 0,
std::string  common_frame = std::string("base_footprint") 
)

The function that performs the whole grasp adjustment.

This description is displayed lower in the doxygen as an extended description along with the above brief description.

Parameters:
grasp_poseThe starting pose for evaluation.
adjusted_posesA vector for returning the candidate poses.
search_modeSelects between a local or global search or single pose (which is for debugging).
common_frameThe frame to which everything is transformed (base_footprint is probably the best).

Definition at line 221 of file grasp_adjust.cpp.

int GraspAdjust::findGrasps ( const geometry_msgs::PoseStamped &  grasp_pose_in,
std::priority_queue< GripperModel, std::vector< GripperModel >, GripperModel::compareModels > *  ranked_poses,
int  search_mode = 0,
std::string  common_frame = std::string("base_footprint") 
)

The function that performs the whole grasp adjustment.

This description is displayed lower in the doxygen as an extended description along with the above brief description.

Parameters:
grasp_poseThe starting pose for evaluation.
adjusted_posesA vector for returning the candidate poses.
search_modeSelects between a local or global search or single pose (which is for debugging).
common_frameThe frame to which everything is transformed (base_footprint is probably the best).

Definition at line 256 of file grasp_adjust.cpp.

The function that performs the whole grasp adjustment.

This description is displayed lower in the doxygen as an extended description along with the above brief description.

Parameters:
grasp_poseThe starting pose for evaluation.
adjusted_posesA vector for returning the candidate poses.
search_modeSelects between a local or global search or single pose (which is for debugging).
common_frameThe frame to which everything is transformed (base_footprint is probably the best).

Definition at line 110 of file grasp_adjust.cpp.


Member Data Documentation

Definition at line 93 of file grasp_adjust.h.

Definition at line 98 of file grasp_adjust.h.

Definition at line 86 of file grasp_adjust.h.

Definition at line 86 of file grasp_adjust.h.

Definition at line 86 of file grasp_adjust.h.

Definition at line 106 of file grasp_adjust.h.

Definition at line 109 of file grasp_adjust.h.

Definition at line 116 of file grasp_adjust.h.

Definition at line 100 of file grasp_adjust.h.

Definition at line 86 of file grasp_adjust.h.

Definition at line 92 of file grasp_adjust.h.

Definition at line 88 of file grasp_adjust.h.

Definition at line 88 of file grasp_adjust.h.

Definition at line 95 of file grasp_adjust.h.

Definition at line 90 of file grasp_adjust.h.

Definition at line 90 of file grasp_adjust.h.

Definition at line 90 of file grasp_adjust.h.

Definition at line 90 of file grasp_adjust.h.

Definition at line 97 of file grasp_adjust.h.

std::ofstream GraspAdjust::train_file_

Definition at line 113 of file grasp_adjust.h.

Definition at line 112 of file grasp_adjust.h.

Definition at line 102 of file grasp_adjust.h.


The documentation for this class was generated from the following files:


pr2_grasp_adjust
Author(s): Adam Leeper
autogenerated on Fri Jan 3 2014 12:00:29