A class for finding grasp poses. More...
#include <grasp_adjust.h>
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::TransformBroadcaster * | broadcaster_ |
tf::Vector3 | centroid_ |
pcl::PointCloud< PointT > | cloud_in_ |
pcl::PointCloud< PointT > | cloud_out_ |
pcl::PointCloud< PointT > | cloud_process_ |
Config | config_ |
Debug | debug_ |
const GripperModel | DEFAULT_GRIPPER |
bool | got_first_cloud_ |
pcl::PointCloud< PointT > | last_cloud_ |
tf::TransformListener * | listener_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_pvt_ |
ros::Time | now_ |
ros::Publisher * | pub_cloud_ |
ros::Publisher * | pub_cloud_roi_ |
ros::Publisher * | pub_marker_ |
ros::Publisher * | pub_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. |
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.
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.
Definition at line 87 of file grasp_adjust.cpp.
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.
seed | The gripper model starting position for the descent. |
steps | The 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.
grasp_pose | The starting pose for evaluation. |
adjusted_poses | A vector for returning the candidate poses. |
search_mode | Selects between a local or global search or single pose (which is for debugging). |
common_frame | The 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.
grasp_pose | The starting pose for evaluation. |
adjusted_poses | A vector for returning the candidate poses. |
search_mode | Selects between a local or global search or single pose (which is for debugging). |
common_frame | The frame to which everything is transformed (base_footprint is probably the best). |
Definition at line 256 of file grasp_adjust.cpp.
void GraspAdjust::setInputCloud | ( | const pcl::PointCloud< PointT > & | cloud | ) |
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.
grasp_pose | The starting pose for evaluation. |
adjusted_poses | A vector for returning the candidate poses. |
search_mode | Selects between a local or global search or single pose (which is for debugging). |
common_frame | The frame to which everything is transformed (base_footprint is probably the best). |
Definition at line 110 of file grasp_adjust.cpp.
Definition at line 93 of file grasp_adjust.h.
tf::Vector3 GraspAdjust::centroid_ |
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.