pick_and_place.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <std_msgs/String.h>
00003 #include <std_srvs/Trigger.h>
00004 #include <geometry_msgs/PointStamped.h>
00005 #include <trajectory_msgs/JointTrajectory.h>
00006 #include <std_msgs/Empty.h>
00007 #include <tf/transform_listener.h>
00008 #include "tf/message_filter.h"
00009 #include "message_filters/subscriber.h"
00010 #include <actionlib/client/simple_action_client.h>
00011 #include <control_msgs/GripperCommandAction.h>
00012 #include <moveit/move_group_interface/move_group.h>
00013 #include <moveit/kinematics_metrics/kinematics_metrics.h>
00014 #include <moveit_msgs/WorkspaceParameters.h>
00015 #include <moveit/trajectory_processing/iterative_time_parameterization.h>
00016 #include <moveit/planning_scene_interface/planning_scene_interface.h>
00017 #include <std_srvs/SetBool.h>
00018 #include <moveit_msgs/PickupAction.h>
00019 #include <moveit_msgs/PlaceAction.h>
00020 
00021 #define MAX_BOARD_PLACE 0.05
00022 typedef actionlib::SimpleActionClient<moveit_msgs::PickupAction> PickClient;
00023 typedef actionlib::SimpleActionClient<moveit_msgs::PlaceAction> PlaceClient;
00024 
00025 struct Point_t {
00026     float x;
00027     float y;
00028 
00029     Point_t() {
00030         x = y = 0.0;
00031     }
00032 
00033 };
00034 
00035 void look_down();
00036 
00037 bool set_collision_update(bool state);
00038 
00039 moveit_msgs::PickupGoal BuildPickGoal(const std::string &objectName);
00040 
00041 moveit_msgs::PlaceGoal buildPlaceGoal(const std::string &objectName);
00042 
00043 bool pickAndPlaceCallBack(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
00044 
00045 double randBetweenTwoNum(int max, int min);
00046 
00047 bool exec = false;
00048 ros::ServiceClient *uc_client_ptr;
00049 ros::Publisher pub_controller_command;
00050 Point_t point;
00051 
00052 
00053 int main(int argc, char **argv) {
00054 
00055     ros::init(argc, argv, "pick_and_plce_node");
00056     ros::AsyncSpinner spinner(2);
00057     spinner.start();
00058     srand((unsigned int) time(NULL));
00059     ros::NodeHandle n;
00060     ros::NodeHandle pn("~");
00061     std::string object_name,table_name;
00062     std::string startPositionName ;
00063 
00064     pn.param<std::string>("start_position_name", startPositionName, "pre_grasp2");
00065     pn.param<std::string>("object_name", object_name, "can");
00066     pn.param<std::string>("table_name", table_name, "table");
00067 
00068     ros::ServiceServer pickAndPlace = n.advertiseService("pick_go", &pickAndPlaceCallBack);
00069     ROS_INFO("Hello");
00070     moveit::planning_interface::MoveGroup group("arm");
00071     //Config move group
00072     group.setMaxVelocityScalingFactor(0.1);
00073     group.setMaxAccelerationScalingFactor(0.5);
00074     group.setPlanningTime(5.0);
00075     group.setNumPlanningAttempts(10);
00076     group.setPlannerId("RRTConnectkConfigDefault");
00077     group.setPoseReferenceFrame("base_footprint");
00078 
00079     group.setStartStateToCurrentState();
00080     group.setNamedTarget(startPositionName);
00081     moveit::planning_interface::MoveGroup::Plan startPosPlan;
00082     if(group.plan(startPosPlan)) { //Check if plan is valid
00083         group.execute(startPosPlan);
00084         pub_controller_command = n.advertise<trajectory_msgs::JointTrajectory>("/pan_tilt_trajectory_controller/command", 2);
00085         ROS_INFO("Waiting for the moveit action server to come up");
00086         ros::ServiceClient uc_client = n.serviceClient<std_srvs::SetBool>("update_collision_objects");
00087         ROS_INFO("Waiting for update_collision service...");
00088         uc_client.waitForExistence();
00089         uc_client_ptr = &uc_client;
00090         set_collision_update(true);
00091         ros::Duration(10.0).sleep();
00092         look_down();
00093         ROS_INFO("Looking down...");
00094         ROS_INFO("Ready!");
00095     }
00096     else {
00097         ROS_ERROR("Error");
00098     }
00099     ros::waitForShutdown();
00100     return 0;
00101 }
00102 
00103 moveit_msgs::PlaceGoal buildPlaceGoal(const std::string &objectName) {
00104     moveit_msgs::PlaceGoal placeGoal;
00105     placeGoal.group_name = "arm";
00106     placeGoal.attached_object_name = objectName;
00107     placeGoal.place_eef = false;
00108     placeGoal.support_surface_name = "table";
00109     placeGoal.planner_id = "RRTConnectkConfigDefault";
00110     placeGoal.allowed_planning_time = 5.0;
00111     placeGoal.planning_options.replan = true;
00112     placeGoal.planning_options.replan_attempts = 5;
00113     placeGoal.planning_options.replan_delay = 2.0;
00114     placeGoal.planning_options.planning_scene_diff.is_diff = true;
00115     placeGoal.planning_options.planning_scene_diff.robot_state.is_diff = true;
00116     std::vector<moveit_msgs::PlaceLocation> locations;
00117     moveit_msgs::PlaceLocation location;
00118     location.pre_place_approach.direction.header.frame_id = "/base_footprint";
00119     location.pre_place_approach.direction.vector.z = -1.0;
00120     location.pre_place_approach.min_distance = 0.1;
00121     location.pre_place_approach.desired_distance = 0.2;
00122 
00123     location.post_place_retreat.direction.header.frame_id = "/gripper_link";
00124     location.post_place_retreat.direction.vector.x = -1.0;
00125     location.post_place_retreat.min_distance = 0.0;
00126     location.post_place_retreat.desired_distance = 0.2;
00127 
00128     location.place_pose.header.frame_id = placeGoal.support_surface_name;
00129     bool inTheBoard;
00130     do {
00131         inTheBoard = true;
00132         location.place_pose.pose.position.x = randBetweenTwoNum(10, -10);
00133         if(fabs(point.x + location.place_pose.pose.position.x) >= MAX_BOARD_PLACE) {
00134             inTheBoard = false;
00135         }
00136     } while (!inTheBoard);
00137 
00138     do {
00139         inTheBoard = true;
00140         location.place_pose.pose.position.y = randBetweenTwoNum(5, -5);
00141         if(fabs(point.y + location.place_pose.pose.position.y) >= MAX_BOARD_PLACE) {
00142             inTheBoard = false;
00143         }
00144     } while (!inTheBoard);
00145 
00146     location.place_pose.pose.position.z = 0.1;
00147     location.place_pose.pose.orientation.w = 1.0;
00148 
00149     locations.push_back(location);
00150     placeGoal.place_locations = locations;
00151     return placeGoal;
00152 }
00153 
00154 moveit_msgs::PickupGoal BuildPickGoal(const std::string &objectName) {
00155     moveit_msgs::PickupGoal goal;
00156     goal.target_name = objectName;
00157     goal.group_name = "arm";
00158     goal.end_effector = "eef";
00159     goal.allowed_planning_time = 5.0;
00160     goal.planning_options.replan_delay = 2.0;
00161     goal.planning_options.planning_scene_diff.is_diff = true;
00162     goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
00163     goal.planning_options.replan=true;
00164     goal.planning_options.replan_attempts=5;
00165     goal.planner_id = "RRTConnectkConfigDefault";
00166 
00167     goal.minimize_object_distance = true;
00168     moveit_msgs::Grasp g;
00169     g.max_contact_force = 1.00; //0.01
00170     g.grasp_pose.header.frame_id = goal.target_name;
00171     g.grasp_pose.pose.position.x = -0.04;
00172     g.grasp_pose.pose.position.y = 0.0;
00173     g.grasp_pose.pose.position.z = 0.0;
00174     g.grasp_pose.pose.orientation.x = 0.0;
00175     g.grasp_pose.pose.orientation.y = 0.0;
00176     g.grasp_pose.pose.orientation.z = 0.0;
00177     g.grasp_pose.pose.orientation.w = 1.0;
00178 
00179     g.pre_grasp_approach.direction.header.frame_id = "/base_footprint"; //gripper_link
00180     g.pre_grasp_approach.direction.vector.x = 1.0;
00181     g.pre_grasp_approach.min_distance = 0.1;
00182     g.pre_grasp_approach.desired_distance = 0.2;
00183 
00184     g.post_grasp_retreat.direction.header.frame_id = "/base_footprint"; //gripper_link
00185     g.post_grasp_retreat.direction.vector.z = 1.0;
00186     g.post_grasp_retreat.min_distance = 0.1;
00187     g.post_grasp_retreat.desired_distance = 0.2;
00188 
00189     g.pre_grasp_posture.joint_names.push_back("left_finger_joint");
00190     g.pre_grasp_posture.joint_names.push_back("right_finger_joint");
00191     g.pre_grasp_posture.points.resize(1);
00192     g.pre_grasp_posture.points[0].positions.resize(g.pre_grasp_posture.joint_names.size());
00193     g.pre_grasp_posture.points[0].positions[0] = 0.14;
00194 
00195     g.grasp_posture.joint_names = g.pre_grasp_posture.joint_names;
00196     g.grasp_posture.points.resize(1);
00197     g.grasp_posture.points[0].positions.resize(g.grasp_posture.joint_names.size());
00198     g.grasp_posture.points[0].positions[0] = 0.01;
00199     g.grasp_posture.points[0].effort.resize(g.grasp_posture.joint_names.size());
00200     g.grasp_posture.points[0].effort[0] = 0.4;
00201     goal.possible_grasps.push_back(g);
00202     return goal;
00203 }
00204 
00205 void look_down() {
00206 
00207     trajectory_msgs::JointTrajectory traj;
00208     traj.header.stamp = ros::Time::now();
00209     traj.joint_names.push_back("head_pan_joint");
00210     traj.joint_names.push_back("head_tilt_joint");
00211     traj.points.resize(1);
00212     traj.points[0].time_from_start = ros::Duration(1.0);
00213     std::vector<double> q_goal(2);
00214     q_goal[0]=0.0;
00215     q_goal[1]=0.6;
00216     traj.points[0].positions=q_goal;
00217     traj.points[0].velocities.push_back(0);
00218     traj.points[0].velocities.push_back(0);
00219     pub_controller_command.publish(traj);
00220 }
00221 
00222 bool set_collision_update(bool state){
00223     std_srvs::SetBool srv;
00224     srv.request.data=state;
00225     if (uc_client_ptr->call(srv))
00226     {
00227         ROS_INFO("update_colision response: %s", srv.response.message.c_str());
00228         return true;
00229     }
00230     else
00231     {
00232         ROS_ERROR("Failed to call service /find_objects_node/update_colision");
00233         return false;
00234     }
00235 
00236 }
00237 
00238 bool pickAndPlaceCallBack(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) {
00239     ros::NodeHandle pn("~");
00240     ros::NodeHandle n;
00241     std::string object_name;
00242 
00243     pn.param<std::string>("object_name", object_name, "can");
00244 
00245     ros::ServiceClient uc_client = n.serviceClient<std_srvs::SetBool>("update_collision_objects");
00246     std_srvs::SetBool disableColl;
00247     disableColl.request.data = false;
00248 
00249     if(uc_client.call(disableColl)) {
00250         ROS_INFO("update_colision response: OFF ");
00251     }
00252 
00253     PickClient pickClient("pickup", true);
00254     pickClient.waitForServer();
00255 
00256     moveit_msgs::PickupGoal pickGoal = BuildPickGoal(object_name);
00257     actionlib::SimpleClientGoalState pickStatus = pickClient.sendGoalAndWait(pickGoal);
00258     if(pickStatus != actionlib::SimpleClientGoalState::SUCCEEDED) {
00259         res.success = (unsigned char) false;
00260         res.message = pickStatus.getText();
00261         point.x = point.y = 0;
00262     }
00263     else {
00264         PlaceClient placeClient("place", true);
00265         placeClient.waitForServer();
00266         bool found = false;
00267         do {
00268             moveit_msgs::PlaceGoal placeGoal = buildPlaceGoal(object_name);
00269             actionlib::SimpleClientGoalState placeStatus = placeClient.sendGoalAndWait(placeGoal);
00270             if (placeStatus == actionlib::SimpleClientGoalState::SUCCEEDED) {
00271                 found = true;
00272                 res.success = (unsigned char) (found);
00273                 res.message = placeStatus.getText();
00274                 point.x += placeGoal.place_locations[0].place_pose.pose.position.x;
00275                 point.y += placeGoal.place_locations[0].place_pose.pose.position.y;
00276             }
00277         } while(!found);
00278     }
00279 
00280     std_srvs::SetBool enableColl;
00281     enableColl.request.data = true;
00282     if(uc_client.call(enableColl)) {
00283         ROS_INFO("update_colision response: ON ");
00284     }
00285 
00286     return true;
00287 
00288 
00289 }
00290 double randBetweenTwoNum(int max, int min) {
00291     int randomNum = rand()%(max-min + 1) + min;
00292     return randomNum / 100.0;
00293 }


robotican_demos
Author(s):
autogenerated on Fri Oct 27 2017 03:02:45