object_pick_and_place_simple.cpp
Go to the documentation of this file.
1 /*
2  * [c++ gripper example] object pick and place for doosan robot
3  * Author: Jin Hyuk Gong (jinhyuk.gong@doosan.com)
4  *
5  * Copyright (c) 2019 Doosan Robotics
6  * Use of this source code is governed by the BSD, see LICENSE
7 */
8 
9 #include <ros/ros.h>
10 #include <signal.h>
11 #include <boost/thread/thread.hpp>
12 
13 #include "dsr_util.h"
14 #include "dsr_robot.h"
15 
16 using namespace std;
17 using namespace DSR_Robot;
18 
19 //----- set tartget robot----------------------------------------------------
20 string ROBOT_ID = "dsr01";
21 string ROBOT_MODEL = "m1013";
22 void SET_ROBOT(string id, string model) {ROBOT_ID = id; ROBOT_MODEL= model;}
23 //---------------------------------------------------------------------------
24 
25 int gripper_move(float width)
26 {
27 
28  //ros::ServiceClient srvMoveJoint = nh.serviceClient<dsr_msgs::MoveJoint>("/dsr01m1013/motion/move_joint");
29  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
30  ros::ServiceClient srvRobotiq2FMove = node->serviceClient<dsr_msgs::Robotiq2FMove>("/"+ROBOT_ID + ROBOT_MODEL+"/gripper/robotiq_2f_move");
31  dsr_msgs::Robotiq2FMove srv;
32  srv.request.width = width;
33 
34  if(srvRobotiq2FMove.call(srv))
35  {
36  //ROS_INFO("receive srv, srv.response.success: %ld\n", (long int)srv.response.success);
37  return (srv.response.success);
38  }
39  else
40  {
41  ROS_ERROR("Failed to call service dr_control_service : gripper_move\n");
42  ros::shutdown();
43  return -1;
44  }
45 
46  return 0;
47 }
48 
50 
51 static void thread_subscriber()
52 {
53  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
56  ros::MultiThreadedSpinner spinner(2);
57  spinner.spin();
58 }
59 
60 void SigHandler(int sig)
61 {
62  // Do some custom action.
63  // For example, publish a stop message to some other nodes.
64 
65  // All the default sigint handler does is call shutdown()
66  ROS_INFO("shutdown time! sig=%d",sig);
67  ROS_INFO("shutdown time! sig=%d",sig);
68  ROS_INFO("shutdown time! sig=%d",sig);
69  //ros::ServiceClient srvMoveStop = nh.serviceClient<dsr_msgs::MoveStop>("/dsr01m1013/motion/move_stop");
70 
71  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
72  ros::Publisher pubRobotStop = node->advertise<dsr_msgs::RobotStop>("/"+ROBOT_ID +ROBOT_MODEL+"/stop",100);
73 
74  dsr_msgs::RobotStop msg;
75 
76  msg.stop_mode = STOP_TYPE_QUICK;
77  pubRobotStop.publish(msg);
78 
79  ros::shutdown();
80 }
81 
82 int main(int argc, char** argv)
83 {
84  //----- set target robot ---------------
85  string my_robot_id = "dsr01";
86  string my_robot_model = "m1013";
87  if(1 == argc){
88  ROS_INFO("default arguments: dsr01 m1013");
89  }
90  else{
91  if(3 != argc){
92  ROS_ERROR("invalid arguments: <ns> <model> (ex) dsr01 m1013");
93  exit(1);
94  }
95  for (int i = 1; i < argc; i++){
96  printf("argv[%d] = %s\n", i, argv[i]);
97  }
98  my_robot_id = argv[1];
99  my_robot_model = argv[2];
100  }
101  //std::cout << "my_robot_id= " << my_robot_id << ", my_robot_model= " << my_robot_model << endl;
102  SET_ROBOT(my_robot_id, my_robot_model);
103 
104  //----- init ROS ----------------------
105  ros::init(argc, argv, "object_pick_and_place_simple_cpp", ros::init_options::NoSigintHandler);
106  ros::NodeHandle nh("~");
107  // Override the default ros sigint handler.
108  // This must be set after the first NodeHandle is created.
109  signal(SIGINT, SigHandler);
110  ros::Publisher pubRobotStop = nh.advertise<dsr_msgs::RobotStop>("/"+ROBOT_ID +ROBOT_MODEL+"/stop",10);
112 
113  //----- create DsrRobot ---------------
114  CDsrRobot robot(nh, my_robot_id, my_robot_model);
115 
116  // run subscriber thread (for monitoring)
117  boost::thread thread_sub(thread_subscriber);
118 
120  float p0[6]={0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
121  float p1[6]={0.0, 0.0, 90.0, 0.0, 90.0 , 0.0}; //joint
122  float p2[6]={180.0, 0.0, 90, 0.0, 90.0, 0.0}; //joint
123 
124  float x1[6]={0, 0, -200, 0, 0, 0}; //task
125  float x2[6]={0, 0, 200, 0, 0, 0}; //task
126  float velx[2]={50, 50}; // 태스크 속도를 50(mm/sec), 50(deg/sec)로 설정
127  float accx[2]={100, 100}; // 태스크 가속도를 100(mm/sec2), 100(deg/sec2)로 설정
128 
129  while(ros::ok())
130  {
131  robot.movej(p0, 60, 30);
132  robot.movej(p1, 60, 30);
133 
134  robot.movel(x1, velx, accx, 2, 0.f, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE);
135  gripper_move(0.4); //0.0 - close;
136  ros::Duration(1).sleep();
137  robot.movel(x2, velx, accx, 2, 0.f, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE);
138 
139  robot.movej(p2, 60, 30, 3);
140  robot.movel(x1, velx, accx, 2, 0.f, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE);
141  gripper_move(0.0); //0.8 - open
142  ros::Duration(1).sleep();
143  robot.movel(x2, velx, accx, 2, 0.f, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE);
144  }
145 
146  ROS_INFO("object_pick_and_place_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
147  ROS_INFO("object_pick_and_place_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
148  ROS_INFO("object_pick_and_place_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
149 
151  thread_sub.join();
152 
153  ROS_INFO("object_pick_and_place_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
154  return 0;
155 }
f
float velx[2]
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
float accx[2]
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
void SET_ROBOT(string id, string model)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void shutdown()
int main(int argc, char **argv)
int gripper_move(float width)
void SigHandler(int sig)
static void thread_subscriber()
#define ROS_ERROR(...)


cpp
Author(s): Kab Kyoum Kim , Jin Hyuk Gong , Jeongwoo Lee
autogenerated on Sat May 18 2019 02:32:53