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

#include <gripper_model.h>

List of all members.

Classes

class  compareModels
 A comparison function for Gripper Model sorting. More...

Public Member Functions

bool collidesWithPlane (tf::Pose yz_plane)
double evaluateGrasp (const pcl::PointCloud< PointT > &cloud, FeatureWeights &weights, tf::Vector3 default_centroid, bool debug_print=false, bool weights_as_output_features=false)
 Evaluates the gripper position, returning the cost of the grasp.
 GripperModel ()
void publishModel (ros::Publisher &pub, std::string ns=std::string("gripper_model"), int id=0, ros::Duration lifetime=ros::Duration(5.0), double opacity=1.0, int action=visualization_msgs::Marker::ADD)
void reset (bool resetStateAndScore=false)
void setFrameId (const std::string &frame_id)
void setHeader (const std_msgs::Header &header)
void setStamp (const ros::Time &stamp)
void toPoseStamped (geometry_msgs::PoseStamped &ps)
void transform (const geometry_msgs::Transform &T, const std::string &frame_id="")
void transform (const tf::Transform &T, const std::string &frame_id="")

Public Attributes

Box bounding_box_
Box extended_
std_msgs::Header header
Box l_finger_
ros::NodeHandlenh_ptr_
Box palm_
ros::Publisher pub_
Box r_finger_
Box roi_box_
double score_
Box space_
GraspState state_
tf::Transform tool_frame_
tf::Transform wrist_frame_

Private Types

typedef pcl::PointXYZRGBNormal PointT

Detailed Description

Definition at line 98 of file gripper_model.h.


Member Typedef Documentation

typedef pcl::PointXYZRGBNormal GripperModel::PointT [private]

Definition at line 100 of file gripper_model.h.


Constructor & Destructor Documentation

Definition at line 109 of file gripper_model.h.


Member Function Documentation

double GripperModel::evaluateGrasp ( const pcl::PointCloud< PointT > &  cloud,
FeatureWeights weights,
tf::Vector3  default_centroid,
bool  debug_print = false,
bool  weights_as_output_features = false 
)

Evaluates the gripper position, returning the cost of the grasp.

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

Parameters:
cloud_in
modelThe gripper model representing the current grasp
starting_gripperThe initial gripper model... what is this?
default_centroidTODO fix this
cloudThe cloud chunk under consideration
weightsThe weights to use for evaluating the quality metric
default_centroidThe location of the centroid of the cloud to use in case there are no points within the extended box

Definition at line 245 of file gripper_model.cpp.

void GripperModel::publishModel ( ros::Publisher pub,
std::string  ns = std::string("gripper_model"),
int  id = 0,
ros::Duration  lifetime = ros::Duration(5.0),
double  opacity = 1.0,
int  action = visualization_msgs::Marker::ADD 
)

Definition at line 167 of file gripper_model.cpp.

void GripperModel::reset ( bool  resetStateAndScore = false)

Definition at line 91 of file gripper_model.cpp.

void GripperModel::setFrameId ( const std::string &  frame_id)

Definition at line 58 of file gripper_model.cpp.

void GripperModel::setHeader ( const std_msgs::Header header)

Definition at line 85 of file gripper_model.cpp.

void GripperModel::setStamp ( const ros::Time stamp)

Definition at line 73 of file gripper_model.cpp.

void GripperModel::toPoseStamped ( geometry_msgs::PoseStamped &  ps)

Definition at line 29 of file gripper_model.cpp.

void GripperModel::transform ( const geometry_msgs::Transform &  T,
const std::string &  frame_id = "" 
)

Definition at line 38 of file gripper_model.cpp.

void GripperModel::transform ( const tf::Transform T,
const std::string &  frame_id = "" 
)

Definition at line 44 of file gripper_model.cpp.


Member Data Documentation

Definition at line 120 of file gripper_model.h.

Definition at line 119 of file gripper_model.h.

Definition at line 112 of file gripper_model.h.

Definition at line 116 of file gripper_model.h.

Definition at line 105 of file gripper_model.h.

Definition at line 115 of file gripper_model.h.

Definition at line 106 of file gripper_model.h.

Definition at line 117 of file gripper_model.h.

Definition at line 121 of file gripper_model.h.

Definition at line 127 of file gripper_model.h.

Definition at line 118 of file gripper_model.h.

Definition at line 126 of file gripper_model.h.

Definition at line 123 of file gripper_model.h.

Definition at line 122 of file gripper_model.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