$search
Wraps around database connection to provide database-related services through ROS. More...
Public Member Functions | |
ObjectsDatabaseNode () | |
~ObjectsDatabaseNode () | |
Private Member Functions | |
bool | getDescriptionCB (GetModelDescription::Request &request, GetModelDescription::Response &response) |
Callback for the get description service. | |
bool | getGrasps (const GraspableObject &target, const std::string &arm_name, std::vector< Grasp > &grasps, GraspPlanningErrorCode &error_code) |
bool | getMeshCB (GetModelMesh::Request &request, GetModelMesh::Response &response) |
Callback for the get mesh service. | |
bool | getModelsCB (GetModelList::Request &request, GetModelList::Response &response) |
Callback for the get models service. | |
bool | getScansCB (GetModelScans::Request &request, GetModelScans::Response &response) |
void | graspPlanningActionCB (const object_manipulation_msgs::GraspPlanningGoalConstPtr &goal) |
bool | graspPlanningCB (GraspPlanning::Request &request, GraspPlanning::Response &response) |
Callback for the get grasps service. | |
geometry_msgs::Pose | multiplyPoses (const geometry_msgs::Pose &p1, const geometry_msgs::Pose &p2) |
virtual void | pruneGraspList (std::vector< boost::shared_ptr< DatabaseGrasp > > &grasps, double gripper_threshold, double table_clearance_threshold) |
Prune grasps that require gripper to be open all the way, or that are marked in db as colliding with table. | |
bool | saveScanCB (SaveScan::Request &request, SaveScan::Response &response) |
bool | translateIdCB (TranslateRecognitionId::Request &request, TranslateRecognitionId::Response &response) |
Private Attributes | |
ObjectsDatabase * | database_ |
The database connection itself. | |
ros::ServiceServer | get_description_srv_ |
Server for the get description service. | |
ros::ServiceServer | get_mesh_srv_ |
Server for the get mesh service. | |
ros::ServiceServer | get_models_srv_ |
Server for the get models service. | |
ros::ServiceServer | get_scans_srv_ |
Server for the get scans service. | |
actionlib::SimpleActionServer < object_manipulation_msgs::GraspPlanningAction > * | grasp_planning_server_ |
The action server for grasping planning. | |
ros::ServiceServer | grasp_planning_srv_ |
Server for the get grasps service. | |
tf::TransformListener | listener_ |
Transform listener. | |
ros::NodeHandle | priv_nh_ |
Node handle in the private namespace. | |
double | prune_gripper_opening_ |
Threshold for pruning grasps based on gripper opening. | |
double | prune_table_clearance_ |
Threshold for pruning grasps based on table clearance. | |
ros::NodeHandle | root_nh_ |
Node handle in the root namespace. | |
ros::ServiceServer | save_scan_srv_ |
Server for the save scan service. | |
ros::ServiceServer | translate_id_srv_ |
Server for the id translation service. |
Wraps around database connection to provide database-related services through ROS.
Contains very thin wrappers for getting a list of scaled models and for getting the mesh of a model, as well as a complete server for the grasp planning service
Definition at line 138 of file objects_database_node.cpp.
ObjectsDatabaseNode::ObjectsDatabaseNode | ( | ) | [inline] |
Definition at line 529 of file objects_database_node.cpp.
ObjectsDatabaseNode::~ObjectsDatabaseNode | ( | ) | [inline] |
Definition at line 577 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::getDescriptionCB | ( | GetModelDescription::Request & | request, | |
GetModelDescription::Response & | response | |||
) | [inline, private] |
Callback for the get description service.
Definition at line 251 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::getGrasps | ( | const GraspableObject & | target, | |
const std::string & | arm_name, | |||
std::vector< Grasp > & | grasps, | |||
GraspPlanningErrorCode & | error_code | |||
) | [inline, private] |
Definition at line 355 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::getMeshCB | ( | GetModelMesh::Request & | request, | |
GetModelMesh::Response & | response | |||
) | [inline, private] |
Callback for the get mesh service.
Definition at line 234 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::getModelsCB | ( | GetModelList::Request & | request, | |
GetModelList::Response & | response | |||
) | [inline, private] |
Callback for the get models service.
Definition at line 212 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::getScansCB | ( | GetModelScans::Request & | request, | |
GetModelScans::Response & | response | |||
) | [inline, private] |
Definition at line 275 of file objects_database_node.cpp.
void ObjectsDatabaseNode::graspPlanningActionCB | ( | const object_manipulation_msgs::GraspPlanningGoalConstPtr & | goal | ) | [inline, private] |
Definition at line 495 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::graspPlanningCB | ( | GraspPlanning::Request & | request, | |
GraspPlanning::Response & | response | |||
) | [inline, private] |
Callback for the get grasps service.
Definition at line 489 of file objects_database_node.cpp.
geometry_msgs::Pose ObjectsDatabaseNode::multiplyPoses | ( | const geometry_msgs::Pose & | p1, | |
const geometry_msgs::Pose & | p2 | |||
) | [inline, private] |
Definition at line 341 of file objects_database_node.cpp.
virtual void ObjectsDatabaseNode::pruneGraspList | ( | std::vector< boost::shared_ptr< DatabaseGrasp > > & | grasps, | |
double | gripper_threshold, | |||
double | table_clearance_threshold | |||
) | [inline, private, virtual] |
Prune grasps that require gripper to be open all the way, or that are marked in db as colliding with table.
Use negative value for table_clearance_threshold if no clearing should be done based on table clearance.
Definition at line 313 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::saveScanCB | ( | SaveScan::Request & | request, | |
SaveScan::Response & | response | |||
) | [inline, private] |
Definition at line 289 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::translateIdCB | ( | TranslateRecognitionId::Request & | request, | |
TranslateRecognitionId::Response & | response | |||
) | [inline, private] |
Definition at line 183 of file objects_database_node.cpp.
ObjectsDatabase* ObjectsDatabaseNode::database_ [private] |
The database connection itself.
Definition at line 172 of file objects_database_node.cpp.
Server for the get description service.
Definition at line 154 of file objects_database_node.cpp.
Server for the get mesh service.
Definition at line 151 of file objects_database_node.cpp.
Server for the get models service.
Definition at line 148 of file objects_database_node.cpp.
Server for the get scans service.
Definition at line 163 of file objects_database_node.cpp.
actionlib::SimpleActionServer<object_manipulation_msgs::GraspPlanningAction>* ObjectsDatabaseNode::grasp_planning_server_ [private] |
The action server for grasping planning.
Definition at line 160 of file objects_database_node.cpp.
Server for the get grasps service.
Definition at line 157 of file objects_database_node.cpp.
Transform listener.
Definition at line 175 of file objects_database_node.cpp.
ros::NodeHandle ObjectsDatabaseNode::priv_nh_ [private] |
Node handle in the private namespace.
Definition at line 142 of file objects_database_node.cpp.
double ObjectsDatabaseNode::prune_gripper_opening_ [private] |
Threshold for pruning grasps based on gripper opening.
Definition at line 178 of file objects_database_node.cpp.
double ObjectsDatabaseNode::prune_table_clearance_ [private] |
Threshold for pruning grasps based on table clearance.
Definition at line 181 of file objects_database_node.cpp.
ros::NodeHandle ObjectsDatabaseNode::root_nh_ [private] |
Node handle in the root namespace.
Definition at line 145 of file objects_database_node.cpp.
Server for the save scan service.
Definition at line 166 of file objects_database_node.cpp.
Server for the id translation service.
Definition at line 169 of file objects_database_node.cpp.