00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <utility>
00036 #include <algorithm>
00037 #include <string>
00038 #include <functional>
00039
00040 #include <time.h>
00041
00042 #include <boost/foreach.hpp>
00043 #include <boost/lexical_cast.hpp>
00044
00045 #include <boost/shared_ptr.hpp>
00046 using boost::shared_ptr;
00047
00048 #include <ros/ros.h>
00049
00050 #include <object_manipulation_msgs/Grasp.h>
00051 #include <object_manipulation_msgs/GraspableObject.h>
00052 #include <object_manipulation_msgs/GraspPlanning.h>
00053
00054 #include <object_manipulator/tools/grasp_marker_publisher.h>
00055
00056 #include <household_objects_database/objects_database.h>
00057 using household_objects_database::ObjectsDatabasePtr;
00058
00059 #include "bayesian_grasp_planner/bayesian_grasp_planner.h"
00060
00061 namespace bayesian_grasp_planner {
00062
00063 static const std::string PLANNING_MARKERS_OUT_NAME = "grasp_planning_markers";
00064
00065 class BayesianGraspPlannerNode
00066 {
00067 private:
00068
00069 ros::NodeHandle priv_nh_;
00070 ros::NodeHandle root_nh_;
00071
00073 ros::ServiceClient object_detection_srv_;
00075 ros::ServiceClient grasp_planning_srv_;
00076
00078 ros::ServiceServer grasp_execution_srv_;
00079
00081 ros::ServiceServer grasp_test_srv_;
00082
00084 object_manipulator::GraspMarkerPublisher debug_grasp_marker_pub_;
00085
00087 object_manipulator::GraspMarkerPublisher results_grasp_marker_pub_;
00088
00090 object_manipulator::GraspMarkerPublisher rank_grasp_marker_pub_;
00091
00092 ObjectsDatabasePtr database_;
00093
00094
00095
00097 BayesianGraspPlannerPtr planner_;
00098
00100 bool initializeDatabase();
00101
00103 bool graspPlanningCB(object_manipulation_msgs::GraspPlanning::Request &request,
00104 object_manipulation_msgs::GraspPlanning::Response &response);
00105
00107 bool graspTestCB(object_manipulation_msgs::GraspPlanning::Request &request,
00108 object_manipulation_msgs::GraspPlanning::Response &response);
00109
00110
00111 public:
00112 BayesianGraspPlannerNode();
00113 virtual ~BayesianGraspPlannerNode();
00114 };
00115
00116 BayesianGraspPlannerNode::BayesianGraspPlannerNode(): priv_nh_("~"),
00117 root_nh_(""),
00118 debug_grasp_marker_pub_(PLANNING_MARKERS_OUT_NAME, "", 5.0),
00119 results_grasp_marker_pub_("final_sorted_grasp_list", "", 5.0),
00120 rank_grasp_marker_pub_("debug_ranked_grasp_list", "", 5.0)
00121
00122 {
00123 if ( !initializeDatabase() ) ros::shutdown();
00124 planner_.reset(new BayesianGraspPlanner(database_));
00125
00126
00127
00128
00129
00130 grasp_execution_srv_ = root_nh_.advertiseService("probabilistic_grasp_planning",
00131 &BayesianGraspPlannerNode::graspPlanningCB, this);
00132
00133 grasp_test_srv_ = root_nh_.advertiseService("test_grasp_on_probabilistic_planner",
00134 &BayesianGraspPlannerNode::graspTestCB, this);
00135
00136
00137 ROS_INFO("Robust grasp planner service ready");
00138 }
00139
00140
00141 bool BayesianGraspPlannerNode::initializeDatabase()
00142 {
00143
00144 std::string database_host, database_port, database_user, database_pass, database_name;
00145 root_nh_.param<std::string> ("household_objects_database/database_host", database_host, "wgs36");
00146
00147 int port_int;
00148 root_nh_.param<int> ("household_objects_database/database_port", port_int, 5432);
00149
00150 std::stringstream ss;
00151 ss << port_int;
00152 database_port = ss.str();
00153 root_nh_.param<std::string> ("household_objects_database/database_user", database_user, "willow");
00154 root_nh_.param<std::string> ("household_objects_database/database_pass", database_pass, "willow");
00155 root_nh_.param<std::string> ("household_objects_database/database_name", database_name, "household_objects");
00156 database_.reset(new household_objects_database::ObjectsDatabase(database_host, database_port, database_user,
00157 database_pass, database_name));
00158 if (!database_->isConnected())
00159 {
00160 ROS_ERROR("Failed to open model database on host %s, port %s, user %s with password %s, database %s",
00161 database_host.c_str(), database_port.c_str(), database_user.c_str(), database_pass.c_str(),
00162 database_name.c_str());
00163 database_.reset();
00164 return false;
00165 }
00166 return true;
00167 }
00168
00169 bool BayesianGraspPlannerNode::graspPlanningCB(object_manipulation_msgs::GraspPlanning::Request &request,
00170 object_manipulation_msgs::GraspPlanning::Response &response)
00171 {
00172
00173 if (request.grasps_to_evaluate.size() > 0)
00174 {
00175 ROS_WARN("Grasps in test list, but grasp planner was called");
00176 }
00177 else
00178 {
00179 planner_->plan(request.arm_name, request.target, response.grasps);
00180 }
00181 ROS_INFO("Probabilistic grasp planner: returning %zd grasps", response.grasps.size());
00182 response.error_code.value = response.error_code.SUCCESS;
00183 return true;
00184 }
00185
00186 bool BayesianGraspPlannerNode::graspTestCB(object_manipulation_msgs::GraspPlanning::Request &request,
00187 object_manipulation_msgs::GraspPlanning::Response &response)
00188 {
00189
00190 if (request.grasps_to_evaluate.size() > 0)
00191 {
00192 planner_->plan(request.arm_name, request.target, request.grasps_to_evaluate);
00193 response.grasps = request.grasps_to_evaluate;
00194 }
00195 else
00196 {
00197 ROS_WARN("Grasp test service called but no grasps given to test");
00198 }
00199 ROS_INFO("Probabilistic grasp planner: tested %zd grasps", response.grasps.size());
00200 response.error_code.value = response.error_code.SUCCESS;
00201 return true;
00202 }
00203
00204
00205 BayesianGraspPlannerNode::~BayesianGraspPlannerNode()
00206 {
00207 }
00208
00209 }
00210
00211 int main(int argc, char** argv)
00212 {
00213 ros::init(argc, argv, "bayesian_grasp_planner_node");
00214 bayesian_grasp_planner::BayesianGraspPlannerNode node;
00215 ros::spin();
00216 return 0;
00217 }