Classes | Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
GraspLocalizer Class Reference

Repeatedly search for antipodal grasps in point clouds. More...

#include <grasp_localizer.h>

List of all members.

Classes

struct  Parameters
 Parameters for hand search and handle search. More...

Public Member Functions

 GraspLocalizer (ros::NodeHandle &node, const std::string &cloud_topic, const std::string &cloud_frame, int cloud_type, const std::string &svm_file_name, const Parameters &params)
 Constructor.
void localizeGrasps ()
 Repeatedly localize grasps in the input point cloud.
 ~GraspLocalizer ()
 Destructor.

Private Member Functions

void cloud_callback (const sensor_msgs::PointCloud2ConstPtr &msg)
 Callback function for the ROS topic that contains the input point cloud.
void cloud_sized_callback (const agile_grasp::CloudSized &msg)
 Callback function for the ROS topic that contains the input point cloud.
agile_grasp::Grasp createGraspMsg (const Handle &handle)
 Create a grasp message from a handle.
agile_grasp::Grasp createGraspMsg (const GraspHypothesis &hand)
 Create a grasp message from a grasp hypothesis.
agile_grasp::Grasps createGraspsMsg (const std::vector< Handle > &handles)
 Create a grasps message from a list of handles. The message consists of the "average" handle grasps.
agile_grasp::Grasps createGraspsMsg (const std::vector< GraspHypothesis > &hands)
 Create a grasp message from a list of grasp hypotheses.
agile_grasp::Grasps createGraspsMsgFromHands (const std::vector< Handle > &handles)
 Create a grasps message from a list of handles. The message consists of all the grasps contained in the handles.

Private Attributes

std::vector< GraspHypothesisantipodal_hands_
 the antipodal grasps predicted by the SVM
std::string cloud_frame_
 the coordinate frame of the point cloud
PointCloud::Ptr cloud_left_
PointCloud::Ptr cloud_right_
 the point clouds
ros::Subscriber cloud_sub_
 the subscriber for the point cloud topic
ros::Publisher grasps_pub_
 the publisher for the antipodal grasps
std::vector< Handlehandles_
 the handles found by the handle search
std::vector< GraspHypothesishands_
 the grasp hypotheses found by the hand search
Localizationlocalization_
 a pointer to a localization object
int min_inliers_
 the minimum number of inliers for the handle search
int num_clouds_
 the maximum number of point clouds that can be received
int num_clouds_received_
 the number of point clouds that have been received
int size_left_
 the size of the first point cloud
std::string svm_file_name_
 the location and filename of the SVM

Static Private Attributes

static const int CLOUD_SIZED = 1
 agile_grasp/CloudSized
static const int POINT_CLOUD_2 = 0
 sensor_msgs/PointCloud2

Detailed Description

Repeatedly search for antipodal grasps in point clouds.

GraspLocalizer class

This class is a ROS node that repeatedly takes a point cloud from a given ROS topic as input, searches for antipodal grasps in that cloud, and publishes the results on a ROS topic. Incoming point cloud messages can be of two different types: (1) standard sensor_msgs/PointCloud2, (2) agile_grasp/CloudSized messages. The second type is for two point clouds send in the same message (see msg/CloudSized.msg or rosmsg agile_grasp/CloudSized).

Definition at line 69 of file grasp_localizer.h.


Constructor & Destructor Documentation

GraspLocalizer::GraspLocalizer ( ros::NodeHandle node,
const std::string &  cloud_topic,
const std::string &  cloud_frame,
int  cloud_type,
const std::string &  svm_file_name,
const Parameters params 
)

Constructor.

Parameters:
nodethe ROS node
cloud_topicthe ROS topic that contains the input point cloud
cloud_framethe coordinate frame of the point cloud
cloud_typethe type of the point cloud message (see constants for input point cloud types)
svm_file_namethe location and filename of the SVM
paramsa set of parameters for hand search and handle search

Definition at line 4 of file grasp_localizer.cpp.

Destructor.

Definition at line 117 of file grasp_localizer.h.


Member Function Documentation

void GraspLocalizer::cloud_callback ( const sensor_msgs::PointCloud2ConstPtr &  msg) [private]

Callback function for the ROS topic that contains the input point cloud.

Parameters:
msgthe incoming ROS message (of type sensor_msgs/PointCloud2)

Definition at line 40 of file grasp_localizer.cpp.

void GraspLocalizer::cloud_sized_callback ( const agile_grasp::CloudSized &  msg) [private]

Callback function for the ROS topic that contains the input point cloud.

Parameters:
msgthe incoming ROS message (of type agile_grasp/CloudSized)

Definition at line 63 of file grasp_localizer.cpp.

agile_grasp::Grasp GraspLocalizer::createGraspMsg ( const Handle handle) [private]

Create a grasp message from a handle.

Parameters:
handlesthe handle from which the grasp message is created

Definition at line 179 of file grasp_localizer.cpp.

agile_grasp::Grasp GraspLocalizer::createGraspMsg ( const GraspHypothesis hand) [private]

Create a grasp message from a grasp hypothesis.

Parameters:
handthe grasp hypothesis from which the grasp message is created

Definition at line 137 of file grasp_localizer.cpp.

agile_grasp::Grasps GraspLocalizer::createGraspsMsg ( const std::vector< Handle > &  handles) [private]

Create a grasps message from a list of handles. The message consists of the "average" handle grasps.

Parameters:
handlesthe set of handles from which the grasps message is created

Definition at line 168 of file grasp_localizer.cpp.

agile_grasp::Grasps GraspLocalizer::createGraspsMsg ( const std::vector< GraspHypothesis > &  hands) [private]

Create a grasp message from a list of grasp hypotheses.

Parameters:
handsthe set of grasp hypotheses from which the grasps message is created

Definition at line 123 of file grasp_localizer.cpp.

agile_grasp::Grasps GraspLocalizer::createGraspsMsgFromHands ( const std::vector< Handle > &  handles) [private]

Create a grasps message from a list of handles. The message consists of all the grasps contained in the handles.

Parameters:
handlesthe set of handles from which the grasps message is created

Definition at line 149 of file grasp_localizer.cpp.

Repeatedly localize grasps in the input point cloud.

Definition at line 80 of file grasp_localizer.cpp.


Member Data Documentation

the antipodal grasps predicted by the SVM

Definition at line 177 of file grasp_localizer.h.

std::string GraspLocalizer::cloud_frame_ [private]

the coordinate frame of the point cloud

Definition at line 171 of file grasp_localizer.h.

PointCloud::Ptr GraspLocalizer::cloud_left_ [private]

Definition at line 172 of file grasp_localizer.h.

PointCloud::Ptr GraspLocalizer::cloud_right_ [private]

the point clouds

Definition at line 172 of file grasp_localizer.h.

const int GraspLocalizer::CLOUD_SIZED = 1 [static, private]

agile_grasp/CloudSized

Definition at line 186 of file grasp_localizer.h.

the subscriber for the point cloud topic

Definition at line 173 of file grasp_localizer.h.

the publisher for the antipodal grasps

Definition at line 174 of file grasp_localizer.h.

std::vector<Handle> GraspLocalizer::handles_ [private]

the handles found by the handle search

Definition at line 178 of file grasp_localizer.h.

std::vector<GraspHypothesis> GraspLocalizer::hands_ [private]

the grasp hypotheses found by the hand search

Definition at line 176 of file grasp_localizer.h.

a pointer to a localization object

Definition at line 175 of file grasp_localizer.h.

the minimum number of inliers for the handle search

Definition at line 182 of file grasp_localizer.h.

the maximum number of point clouds that can be received

Definition at line 180 of file grasp_localizer.h.

the number of point clouds that have been received

Definition at line 179 of file grasp_localizer.h.

const int GraspLocalizer::POINT_CLOUD_2 = 0 [static, private]

sensor_msgs/PointCloud2

constants for input point cloud types

Definition at line 185 of file grasp_localizer.h.

the size of the first point cloud

Definition at line 181 of file grasp_localizer.h.

std::string GraspLocalizer::svm_file_name_ [private]

the location and filename of the SVM

Definition at line 170 of file grasp_localizer.h.


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


agile_grasp
Author(s): Andreas ten Pas
autogenerated on Sat Jun 8 2019 20:08:27