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 #include <ros/ros.h>
00031
00032 #include <actionlib/client/simple_action_client.h>
00033
00034 #include <sensor_msgs/point_cloud_conversion.h>
00035 #include <sensor_msgs/Image.h>
00036 #include <sensor_msgs/CameraInfo.h>
00037 #include <sensor_msgs/PointCloud2.h>
00038
00039 #include <stereo_msgs/DisparityImage.h>
00040
00041 #include <object_manipulation_msgs/GraspPlanning.h>
00042 #include <object_manipulation_msgs/PlacePlanning.h>
00043
00044 #include <tf/transform_listener.h>
00045
00046 #include <rgbd_assembler/RgbdAssembly.h>
00047
00048 #include "pr2_gripper_click/GripperClickPickupAction.h"
00049 #include "pr2_gripper_click/GripperClickPlaceAction.h"
00050
00052
00053 class HandDescription
00054 {
00055 private:
00057 ros::NodeHandle root_nh_;
00058
00059 inline std::string getStringParam(std::string name)
00060 {
00061 std::string value;
00062 if (!root_nh_.getParamCached(name, value))
00063 {
00064 ROS_ERROR("Hand description: could not find parameter %s", name.c_str());
00065 }
00066
00067 return value;
00068 }
00069
00070 inline std::vector<std::string> getVectorParam(std::string name)
00071 {
00072 std::vector<std::string> values;
00073 XmlRpc::XmlRpcValue list;
00074 if (!root_nh_.getParamCached(name, list))
00075 {
00076 ROS_ERROR("Hand description: could not find parameter %s", name.c_str());
00077 }
00078 if (list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00079 {
00080 ROS_ERROR("Hand description: bad parameter %s", name.c_str());
00081 }
00082
00083 for (int32_t i=0; i<list.size(); i++)
00084 {
00085 if (list[i].getType() != XmlRpc::XmlRpcValue::TypeString)
00086 {
00087 ROS_ERROR("Hand description: bad parameter %s", name.c_str());
00088 }
00089 values.push_back( static_cast<std::string>(list[i]) );
00090
00091 }
00092 return values;
00093 }
00094
00095 public:
00096 HandDescription() : root_nh_("~") {}
00097
00098 inline std::string handDatabaseName(std::string arm_name)
00099 {
00100 return getStringParam("/hand_description/" + arm_name + "/hand_database_name");
00101 }
00102
00103 inline std::vector<std::string> handJointNames(std::string arm_name)
00104 {
00105 return getVectorParam("/hand_description/" + arm_name + "/hand_joints");
00106 }
00107
00108 };
00109
00110 class GraspPlanningGripperClick
00111 {
00112 private:
00113 ros::NodeHandle root_nh_;
00114
00115 ros::NodeHandle priv_nh_;
00116
00117 ros::ServiceServer grasp_srv;
00118 ros::ServiceServer place_srv;
00119
00120 ros::ServiceClient rgbd_assembly_srv_;
00121 std::string rgbd_assembly_service_name_;
00122 bool use_assembler_;
00123
00124 tf::TransformListener listener_;
00125
00126 actionlib::SimpleActionClient<pr2_gripper_click::GripperClickPickupAction> *pickup_action_client_;
00127 actionlib::SimpleActionClient<pr2_gripper_click::GripperClickPlaceAction> *place_action_client_;
00128
00129 std::string grasp_planning_service_topic_;
00130 std::string place_planning_service_topic_;
00131
00132 std::string pickup_action_topic_;
00133 std::string place_action_topic_;
00134
00135 HandDescription hd_;
00136
00137 std::string image_topic_;
00138 std::string disparity_image_topic_;
00139 std::string camera_info_topic_;
00140
00141 bool callSensorDataAssembler(pr2_gripper_click::GripperClickSensorData &sensor_data)
00142 {
00143 rgbd_assembler::RgbdAssembly srv;
00144 if (!ros::service::waitForService(rgbd_assembly_service_name_, ros::Duration(2.0)))
00145 {
00146 ROS_ERROR("rgbd assembler at %s is not available", rgbd_assembly_service_name_.c_str());
00147 return false;
00148 }
00149 if (!rgbd_assembly_srv_.call(srv))
00150 {
00151 ROS_ERROR("Failed to call rgbd assembler at %s", rgbd_assembly_service_name_.c_str());
00152 return false;
00153 }
00154 if (srv.response.result != srv.response.SUCCESS)
00155 {
00156 ROS_ERROR("Rgbd assembler returned an error");
00157 return false;
00158 }
00159 sensor_data.image = srv.response.image;
00160 sensor_data.disparity_image = srv.response.disparity_image;
00161 sensor_data.camera_info = srv.response.camera_info;
00162 return true;
00163 }
00164
00165 bool assembleSensorData(pr2_gripper_click::GripperClickSensorData &sensor_data,
00166 ros::Duration time_out)
00167 {
00168 sensor_msgs::Image::ConstPtr recent_image;
00169 stereo_msgs::DisparityImage::ConstPtr recent_disparity_image;
00170 sensor_msgs::CameraInfo::ConstPtr recent_camera_info;
00171
00172 ROS_INFO("Planning with gripper click: waiting for messages...");
00173 ros::Time start_time = ros::Time::now();
00174 while ((!recent_image || !recent_disparity_image || !recent_camera_info) && priv_nh_.ok())
00175 {
00176 if (!recent_image)
00177 {
00178 ROS_INFO_STREAM(" Waiting for image message on topic " << image_topic_);
00179 recent_image = ros::topic::waitForMessage<sensor_msgs::Image>(image_topic_, root_nh_, ros::Duration(0.5));
00180 }
00181 if (!recent_disparity_image)
00182 {
00183 ROS_INFO_STREAM(" Waiting for disparity image message on topic " << disparity_image_topic_);
00184 recent_disparity_image = ros::topic::waitForMessage<stereo_msgs::DisparityImage>
00185 (disparity_image_topic_, root_nh_, ros::Duration(0.5));
00186 }
00187 if (!recent_camera_info)
00188 {
00189 ROS_INFO_STREAM(" Waiting for camera info message on topic " << camera_info_topic_);
00190 recent_camera_info = ros::topic::waitForMessage<sensor_msgs::CameraInfo>
00191 (camera_info_topic_, root_nh_, ros::Duration(0.5));
00192 }
00193 ros::Time current_time = ros::Time::now();
00194 if (time_out >= ros::Duration(0) && current_time - start_time >= time_out)
00195 {
00196 ROS_INFO("Timed out");
00197 return false;
00198 }
00199 }
00200 if (!priv_nh_.ok()) return false;
00201 ROS_INFO("All required messages received");
00202
00203 sensor_data.image = *recent_image;
00204 sensor_data.disparity_image = *recent_disparity_image;
00205 sensor_data.camera_info = *recent_camera_info;
00206 return true;
00207 }
00208
00209 bool graspServiceCallback(object_manipulation_msgs::GraspPlanning::Request &request,
00210 object_manipulation_msgs::GraspPlanning::Response &response)
00211 {
00212
00213 delete pickup_action_client_;
00214 pickup_action_client_ = new actionlib::SimpleActionClient<pr2_gripper_click::GripperClickPickupAction>
00215 (pickup_action_topic_, true);
00216 while(!pickup_action_client_->waitForServer(ros::Duration(2.0)) && priv_nh_.ok())
00217 {
00218 ROS_INFO("Waiting for action client on topic %s", pickup_action_topic_.c_str());
00219 }
00220
00221 pr2_gripper_click::GripperClickPickupGoal click_goal;
00222 if (use_assembler_)
00223 {
00224 if (!callSensorDataAssembler(click_goal.sensor_data)) return false;
00225 }
00226 else
00227 {
00228 if (!assembleSensorData(click_goal.sensor_data, ros::Duration(5.0))) return false;
00229 }
00230
00231 pickup_action_client_->sendGoal(click_goal);
00232 while (!pickup_action_client_->waitForResult(ros::Duration(0.5)) && priv_nh_.ok())
00233 {
00234 }
00235 if (!priv_nh_.ok())
00236 {
00237 pickup_action_client_->cancelGoal();
00238 return false;
00239 }
00240
00241 if (pickup_action_client_->getState() != actionlib::SimpleClientGoalState::SUCCEEDED)
00242 {
00243 ROS_INFO("The gripper click grasp action has not succeeded;");
00244 response.error_code.value = response.error_code.OTHER_ERROR;
00245 }
00246 else
00247 {
00248 ROS_INFO("Gripper click grasp has succeeded;");
00249 object_manipulation_msgs::Grasp grasp;
00250
00251 std::vector<std::string> joint_names = hd_.handJointNames(request.arm_name);
00252 grasp.pre_grasp_posture.name = joint_names;
00253 grasp.grasp_posture.name = joint_names;
00254
00255 pr2_gripper_click::GripperClickPickupResultConstPtr result = pickup_action_client_->getResult();
00256 grasp.pre_grasp_posture.position.resize( joint_names.size(), result->gripper_opening / 0.0857 * 0.5);
00257 ROS_INFO("Using gripper angles of %.3f", result->gripper_opening / 0.0857 * 0.5);
00258 grasp.grasp_posture.position.resize( joint_names.size(), 0.0);
00259
00260
00261 grasp.grasp_posture.effort.resize(joint_names.size(), 10000);
00262 grasp.pre_grasp_posture.effort.resize(joint_names.size(), 10000);
00263 geometry_msgs::PoseStamped pose_stamped_in = result->grasp_pose;
00264 pose_stamped_in.header.stamp = ros::Time(0);
00265 geometry_msgs::PoseStamped pose_stamped;
00266 try
00267 {
00268 listener_.transformPose(request.target.reference_frame_id, pose_stamped_in, pose_stamped);
00269 }
00270 catch (tf::TransformException ex)
00271 {
00272 ROS_ERROR("Failed to transform gripper click grasp to %s frame; exception: %s",
00273 pickup_action_client_->getResult()->grasp_pose.header.frame_id.c_str(), ex.what());
00274 response.error_code.value = response.error_code.TF_ERROR;
00275 return true;
00276 }
00277 grasp.grasp_pose = pose_stamped.pose;
00278 grasp.success_probability = 1.0;
00279 response.grasps.push_back(grasp);
00280 response.error_code.value = response.error_code.SUCCESS;
00281 }
00282 return true;
00283 }
00284
00285 bool placeServiceCallback(object_manipulation_msgs::PlacePlanning::Request &request,
00286 object_manipulation_msgs::PlacePlanning::Response &response)
00287 {
00288
00289 delete place_action_client_;
00290 place_action_client_ = new actionlib::SimpleActionClient<pr2_gripper_click::GripperClickPlaceAction>
00291 (place_action_topic_, true);
00292 while(!place_action_client_->waitForServer(ros::Duration(2.0)) && priv_nh_.ok())
00293 {
00294 ROS_INFO("Waiting for action client on topic %s", place_action_topic_.c_str());
00295 }
00296
00297 pr2_gripper_click::GripperClickPlaceGoal click_goal;
00298 if (use_assembler_)
00299 {
00300 if (!callSensorDataAssembler(click_goal.sensor_data)) return false;
00301 }
00302 else
00303 {
00304 if (!assembleSensorData(click_goal.sensor_data, ros::Duration(5.0))) return false;
00305 }
00306
00307 click_goal.object = request.target;
00308 click_goal.grasp_pose = request.grasp_pose;
00309 click_goal.default_orientation = request.default_orientation;
00310
00311 place_action_client_->sendGoal(click_goal);
00312 while (!place_action_client_->waitForResult(ros::Duration(0.5)) && priv_nh_.ok())
00313 {
00314 }
00315 if (!priv_nh_.ok())
00316 {
00317 place_action_client_->cancelGoal();
00318 return false;
00319 }
00320
00321 if (place_action_client_->getState() != actionlib::SimpleClientGoalState::SUCCEEDED)
00322 {
00323 ROS_INFO("The gripper click place action has not succeeded;");
00324 response.error_code.value = response.error_code.OTHER_ERROR;
00325 }
00326 else
00327 {
00328 ROS_INFO("The gripper click place action has succeeded;");
00329
00330 geometry_msgs::PoseStamped pose_stamped_in = place_action_client_->getResult()->place_pose;
00331 pose_stamped_in.header.stamp = ros::Time(0);
00332 geometry_msgs::PoseStamped pose_stamped;
00333 try
00334 {
00335 listener_.transformPose("base_link",pose_stamped_in, pose_stamped);
00336 }
00337 catch (tf::TransformException ex)
00338 {
00339 ROS_ERROR("Failed to transform gripper click place to base_link frame; exception: %s", ex.what());
00340 response.error_code.value = response.error_code.TF_ERROR;
00341 return true;
00342 }
00343 response.place_locations.push_back(pose_stamped);
00344 response.error_code.value = response.error_code.SUCCESS;
00345 }
00346 return true;
00347 }
00348
00349 public:
00350 GraspPlanningGripperClick() :
00351 root_nh_(""), priv_nh_("~")
00352 {
00353 priv_nh_.param<std::string>("grasp_planning_service_topic", grasp_planning_service_topic_,
00354 "/grasp_planning_gripper_click");
00355 grasp_srv = root_nh_.advertiseService(grasp_planning_service_topic_,
00356 &GraspPlanningGripperClick::graspServiceCallback, this);
00357
00358 priv_nh_.param<std::string>("pickup_action_topic", pickup_action_topic_, "/gripper_click_pickup_ui");
00359 pickup_action_client_ = new actionlib::SimpleActionClient<pr2_gripper_click::GripperClickPickupAction>
00360 (pickup_action_topic_, true);
00361
00362 priv_nh_.param<std::string>("place_planning_service_topic", place_planning_service_topic_,
00363 "/place_planning_gripper_click");
00364 place_srv = root_nh_.advertiseService(place_planning_service_topic_,
00365 &GraspPlanningGripperClick::placeServiceCallback, this);
00366
00367 priv_nh_.param<std::string>("place_action_topic", place_action_topic_, "/gripper_click_place_ui");
00368 place_action_client_ = new actionlib::SimpleActionClient<pr2_gripper_click::GripperClickPlaceAction>
00369 (place_action_topic_, true);
00370
00371 priv_nh_.param<std::string>("image_topic", image_topic_, "undefined");
00372 priv_nh_.param<std::string>("disparity_image_topic", disparity_image_topic_, "undefined");
00373 priv_nh_.param<std::string>("camera_info_topic", camera_info_topic_, "undefined");
00374
00375 priv_nh_.param<bool>("use_assembler", use_assembler_, true);
00376 priv_nh_.param<std::string>("rgbd_assembly_service_name", rgbd_assembly_service_name_, "/rgbd_assembly");
00377
00378 if (use_assembler_)
00379 {
00380 while(!ros::service::waitForService(rgbd_assembly_service_name_, ros::Duration(2.0)) && priv_nh_.ok())
00381 {
00382 ROS_WARN("waiting for rgbd assembler at %s", rgbd_assembly_service_name_.c_str());
00383 }
00384 }
00385 rgbd_assembly_srv_ = root_nh_.serviceClient<rgbd_assembler::RgbdAssembly>(rgbd_assembly_service_name_, false);
00386
00387 ROS_INFO("Grasp planning gripper click node started");
00388 }
00389 ~GraspPlanningGripperClick()
00390 {
00391 delete pickup_action_client_;
00392 delete place_action_client_;
00393 }
00394 };
00395
00396 int main(int argc, char **argv)
00397 {
00398 ros::init(argc, argv, "grasp_planning_gripper_click_node");
00399 GraspPlanningGripperClick node;
00400 ros::spin();
00401 return 0;
00402 }