The grasp model generator node object. More...
#include <ModelGenerator.h>
Public Member Functions | |
ModelGenerator () | |
Create a ModelGenerator and associated ROS information. | |
bool | okay () const |
A check for a valid ModelGenerator. | |
virtual | ~ModelGenerator () |
Cleans up a ModelGenerator. | |
Static Public Attributes | |
static const bool | DEFAULT_DEBUG = false |
Private Member Functions | |
void | generateAndStoreModels (std::vector< PCLGraspModel > &grasp_models, const int max_model_size, std::vector< uint32_t > &new_model_ids) |
Model generation function. | |
void | generateModelsCallback (const rail_pick_and_place_msgs::GenerateModelsGoalConstPtr &goal) |
Main model generation callback. | |
bool | registrationCheck (const PCLGraspModel &base, const PCLGraspModel &target, PCLGraspModel &result) const |
Check the point cloud registration for the two models. | |
Private Attributes | |
actionlib::SimpleActionServer < rail_pick_and_place_msgs::GenerateModelsAction > | as_ |
bool | debug_ |
ros::Publisher | debug_pc_pub_ |
ros::Publisher | debug_poses_pub_ |
graspdb::Client * | graspdb_ |
ros::NodeHandle | node_ |
bool | okay_ |
ros::NodeHandle | private_node_ |
The grasp model generator node object.
The grasp model generator allows for generating graspdb models based on registration criteria. An action server is used to provide the model/grasp demonstration IDs to use during registration.
Definition at line 41 of file ModelGenerator.h.
Create a ModelGenerator and associated ROS information.
Creates a ROS node handle and starts the action server.
Definition at line 24 of file ModelGenerator.cpp.
ModelGenerator::~ModelGenerator | ( | ) | [virtual] |
Cleans up a ModelGenerator.
Cleans up any connections used by the ModelGenerator.
Definition at line 63 of file ModelGenerator.cpp.
void ModelGenerator::generateAndStoreModels | ( | std::vector< PCLGraspModel > & | grasp_models, |
const int | max_model_size, | ||
std::vector< uint32_t > & | new_model_ids | ||
) | [private] |
Model generation function.
Attempt to search for valid registration pairs for the given models up to the max model size. Valid models are saved to the database and a list of IDs is stored in the given vector.
grasp_models | The array of grasp models to attempt to generate models for. |
max_model_size | The maximum number of grasps allowed per model. |
new_model_ids | The vector to fill with the new grasp model IDs. |
Definition at line 137 of file ModelGenerator.cpp.
void ModelGenerator::generateModelsCallback | ( | const rail_pick_and_place_msgs::GenerateModelsGoalConstPtr & | goal | ) | [private] |
Main model generation callback.
The main callback for the model generation action server.
goal | The goal specifying the parameters for the model generation. |
Definition at line 77 of file ModelGenerator.cpp.
bool ModelGenerator::okay | ( | ) | const |
A check for a valid ModelGenerator.
This function will return true if the appropriate connections were created successfully during initialization.
Definition at line 71 of file ModelGenerator.cpp.
bool ModelGenerator::registrationCheck | ( | const PCLGraspModel & | base, |
const PCLGraspModel & | target, | ||
PCLGraspModel & | result | ||
) | const [private] |
Check the point cloud registration for the two models.
Attempt to merge the two models into a single model. If the model passes the criteria, the result model is filled with the corresponding model.
base | The base model to compare to. |
target | The target model to compare against the base model. |
new_model_ids | The resuliting model (if valid) |
Definition at line 306 of file ModelGenerator.cpp.
actionlib::SimpleActionServer<rail_pick_and_place_msgs::GenerateModelsAction> rail::pick_and_place::ModelGenerator::as_ [private] |
The main model generation action server.
Definition at line 114 of file ModelGenerator.h.
bool rail::pick_and_place::ModelGenerator::debug_ [private] |
The debug flag.
Definition at line 107 of file ModelGenerator.h.
The debug topic publisher.
Definition at line 116 of file ModelGenerator.h.
Definition at line 116 of file ModelGenerator.h.
const bool rail::pick_and_place::ModelGenerator::DEFAULT_DEBUG = false [static] |
If a topic should be created to display debug information such as model point clouds.
Definition at line 45 of file ModelGenerator.h.
The grasp database connection.
Definition at line 109 of file ModelGenerator.h.
The public and private ROS node handles.
Definition at line 112 of file ModelGenerator.h.
bool rail::pick_and_place::ModelGenerator::okay_ [private] |
Definition at line 107 of file ModelGenerator.h.
Definition at line 112 of file ModelGenerator.h.