Wraps around database connection to provide database-related services through ROS. More...
Public Member Functions | |
ObjectsDatabaseNode (const robot_model::RobotModelConstPtr &robot_model) | |
ObjectsDatabaseNode () | |
~ObjectsDatabaseNode () | |
~ObjectsDatabaseNode () | |
Private Member Functions | |
geometry_msgs::Vector3 | approachDirection (const std::string &name, bool &found) |
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 | 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 | getModelsCB (GetModelList::Request &request, GetModelList::Response &response) |
Callback for the get models service. | |
bool | getScansCB (GetModelScans::Request &request, GetModelScans::Response &response) |
std::vector< double > | getVectorDoubleParam (const std::string &name) |
void | graspPlanningActionCB (const manipulation_msgs::GraspPlanningGoalConstPtr &goal) |
bool | graspPlanningCB (GraspPlanning::Request &request, GraspPlanning::Response &response) |
Callback for the get grasps service. | |
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) |
geometry_msgs::Pose | multiplyPoses (const geometry_msgs::Pose &p1, const geometry_msgs::Pose &p2) |
bool | saveScanCB (SaveScan::Request &request, SaveScan::Response &response) |
bool | translateIdCB (TranslateRecognitionId::Request &request, TranslateRecognitionId::Response &response) |
bool | translateIdCB (TranslateRecognitionId::Request &request, TranslateRecognitionId::Response &response) |
void | visualizeGrasps (const std::vector< Grasp > &grasps) |
Private Attributes | |
std::map< std::string, geometry_msgs::Vector3 > | approach_direction_ |
ObjectsDatabase * | database_ |
The database connection itself. | |
std::map< std::string, std::string > | database_hand_ids_ |
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. | |
std::string | grasp_ordering_method_ |
How to order grasps received from database. | |
actionlib::SimpleActionServer < 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. | |
const robot_model::RobotModelConstPtr & | robot_model_ |
ros::NodeHandle | root_nh_ |
Node handle in the root namespace. | |
ros::ServiceServer | save_scan_srv_ |
Server for the save scan service. | |
bool | transform_to_arm_frame_ |
If true, will return results in the frame of the arm link the hand is attached to. | |
ros::ServiceServer | translate_id_srv_ |
Server for the id translation service. | |
ros::Publisher | visualize_grasps_publisher_ |
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 225 of file objects_database_node.cpp.
ObjectsDatabaseNode::ObjectsDatabaseNode | ( | ) | [inline] |
Definition at line 652 of file objects_database_node.cpp.
ObjectsDatabaseNode::~ObjectsDatabaseNode | ( | ) | [inline] |
Definition at line 699 of file objects_database_node.cpp.
ObjectsDatabaseNode::ObjectsDatabaseNode | ( | const robot_model::RobotModelConstPtr & | robot_model | ) | [inline] |
Definition at line 463 of file objects_database_node_simple.cpp.
ObjectsDatabaseNode::~ObjectsDatabaseNode | ( | ) | [inline] |
Definition at line 530 of file objects_database_node_simple.cpp.
geometry_msgs::Vector3 ObjectsDatabaseNode::approachDirection | ( | const std::string & | name, |
bool & | found | ||
) | [inline, private] |
Definition at line 167 of file objects_database_node_simple.cpp.
bool ObjectsDatabaseNode::getDescriptionCB | ( | GetModelDescription::Request & | request, |
GetModelDescription::Response & | response | ||
) | [inline, private] |
Callback for the get description service.
Definition at line 340 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 261 of file objects_database_node_simple.cpp.
bool ObjectsDatabaseNode::getGrasps | ( | const GraspableObject & | target, |
const std::string & | arm_name, | ||
std::vector< Grasp > & | grasps, | ||
GraspPlanningErrorCode & | error_code | ||
) | [inline, private] |
Definition at line 412 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 323 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 120 of file objects_database_node_simple.cpp.
bool ObjectsDatabaseNode::getModelsCB | ( | GetModelList::Request & | request, |
GetModelList::Response & | response | ||
) | [inline, private] |
Callback for the get models service.
Definition at line 301 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::getScansCB | ( | GetModelScans::Request & | request, |
GetModelScans::Response & | response | ||
) | [inline, private] |
Definition at line 364 of file objects_database_node.cpp.
std::vector<double> ObjectsDatabaseNode::getVectorDoubleParam | ( | const std::string & | name | ) | [inline, private] |
Definition at line 142 of file objects_database_node_simple.cpp.
void ObjectsDatabaseNode::graspPlanningActionCB | ( | const manipulation_msgs::GraspPlanningGoalConstPtr & | goal | ) | [inline, private] |
Definition at line 618 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 456 of file objects_database_node_simple.cpp.
bool ObjectsDatabaseNode::graspPlanningCB | ( | GraspPlanning::Request & | request, |
GraspPlanning::Response & | response | ||
) | [inline, private] |
Callback for the get grasps service.
Definition at line 612 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 191 of file objects_database_node_simple.cpp.
geometry_msgs::Pose ObjectsDatabaseNode::multiplyPoses | ( | const geometry_msgs::Pose & | p1, |
const geometry_msgs::Pose & | p2 | ||
) | [inline, private] |
Definition at line 398 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::saveScanCB | ( | SaveScan::Request & | request, |
SaveScan::Response & | response | ||
) | [inline, private] |
Definition at line 378 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::translateIdCB | ( | TranslateRecognitionId::Request & | request, |
TranslateRecognitionId::Response & | response | ||
) | [inline, private] |
Definition at line 204 of file objects_database_node_simple.cpp.
bool ObjectsDatabaseNode::translateIdCB | ( | TranslateRecognitionId::Request & | request, |
TranslateRecognitionId::Response & | response | ||
) | [inline, private] |
Definition at line 272 of file objects_database_node.cpp.
void ObjectsDatabaseNode::visualizeGrasps | ( | const std::vector< Grasp > & | grasps | ) | [inline, private] |
Definition at line 232 of file objects_database_node_simple.cpp.
std::map<std::string, geometry_msgs::Vector3> ObjectsDatabaseNode::approach_direction_ [private] |
Definition at line 106 of file objects_database_node_simple.cpp.
ObjectsDatabase * ObjectsDatabaseNode::database_ [private] |
The database connection itself.
Definition at line 259 of file objects_database_node.cpp.
std::map<std::string, std::string> ObjectsDatabaseNode::database_hand_ids_ [private] |
Definition at line 108 of file objects_database_node_simple.cpp.
Server for the get description service.
Definition at line 241 of file objects_database_node.cpp.
Server for the get mesh service.
Definition at line 238 of file objects_database_node.cpp.
Server for the get models service.
Definition at line 235 of file objects_database_node.cpp.
Server for the get scans service.
Definition at line 250 of file objects_database_node.cpp.
std::string ObjectsDatabaseNode::grasp_ordering_method_ [private] |
How to order grasps received from database.
Transform listener.
Possible values: "random" or "quality"
How to order grasps received from database.
Possible values: "random" or "quality"
Definition at line 266 of file objects_database_node.cpp.
actionlib::SimpleActionServer<manipulation_msgs::GraspPlanningAction>* ObjectsDatabaseNode::grasp_planning_server_ [private] |
The action server for grasping planning.
Definition at line 247 of file objects_database_node.cpp.
Server for the get grasps service.
Definition at line 244 of file objects_database_node.cpp.
Transform listener.
Definition at line 262 of file objects_database_node.cpp.
ros::NodeHandle ObjectsDatabaseNode::priv_nh_ [private] |
Node handle in the private namespace.
Definition at line 229 of file objects_database_node.cpp.
const robot_model::RobotModelConstPtr& ObjectsDatabaseNode::robot_model_ [private] |
Definition at line 117 of file objects_database_node_simple.cpp.
ros::NodeHandle ObjectsDatabaseNode::root_nh_ [private] |
Node handle in the root namespace.
Definition at line 232 of file objects_database_node.cpp.
Server for the save scan service.
Definition at line 253 of file objects_database_node.cpp.
bool ObjectsDatabaseNode::transform_to_arm_frame_ [private] |
If true, will return results in the frame of the arm link the hand is attached to.
Info about how to get to that frame is expected to be found on the param server.
Definition at line 270 of file objects_database_node.cpp.
Server for the id translation service.
Definition at line 256 of file objects_database_node.cpp.
Definition at line 101 of file objects_database_node_simple.cpp.