dsr_simple_test.cpp
Go to the documentation of this file.
1 /*
2  * [c++ example simple] motion basic test 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 
12 #include "dsr_util.h"
13 #include "dsr_robot.h"
14 
15 using namespace std;
16 using namespace DSR_Robot;
17 
18 //----- set tartget robot----------------------------------------------------
19 string ROBOT_ID = "dsr01";
20 string ROBOT_MODEL = "m1013";
21 void SET_ROBOT(string id, string model) {ROBOT_ID = id; ROBOT_MODEL= model;}
22 //---------------------------------------------------------------------------
23 
25 
26 static void thread_subscriber()
27 {
28  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
31  ros::MultiThreadedSpinner spinner(2);
32  spinner.spin();
33 }
34 
35 void SigHandler(int sig)
36 {
37  // Do some custom action.
38  // For example, publish a stop message to some other nodes.
39 
40  // All the default sigint handler does is call shutdown()
41  ROS_INFO("shutdown time! sig=%d",sig);
42  ROS_INFO("shutdown time! sig=%d",sig);
43  ROS_INFO("shutdown time! sig=%d",sig);
44  //ros::ServiceClient srvMoveStop = nh.serviceClient<dsr_msgs::MoveStop>("/dsr01m1013/motion/move_stop");
45 
46  ros::NodeHandlePtr node = boost::make_shared<ros::NodeHandle>();
47  ros::Publisher pubRobotStop = node->advertise<dsr_msgs::RobotStop>("/"+ROBOT_ID +ROBOT_MODEL+"/stop",100);
48 
49  dsr_msgs::RobotStop msg;
50 
51  msg.stop_mode = STOP_TYPE_QUICK;
52  pubRobotStop.publish(msg);
53 
54  ros::shutdown();
55 }
56 
57 int main(int argc, char** argv)
58 {
59  //----- set target robot ---------------
60  string my_robot_id = "dsr01";
61  string my_robot_model = "m1013";
62  if(1 == argc){
63  ROS_INFO("default arguments: dsr01 m1013");
64  }
65  else{
66  if(3 != argc){
67  ROS_ERROR("invalid arguments: <ns> <model> (ex) dsr01 m1013");
68  exit(1);
69  }
70  for (int i = 1; i < argc; i++){
71  printf("argv[%d] = %s\n", i, argv[i]);
72  }
73  my_robot_id = argv[1];
74  my_robot_model = argv[2];
75  }
76  //std::cout << "my_robot_id= " << my_robot_id << ", my_robot_model= " << my_robot_model << endl;
77  SET_ROBOT(my_robot_id, my_robot_model);
78 
79  //----- init ROS ----------------------
80  ros::init(argc, argv, "dsr_service_test_cpp", ros::init_options::NoSigintHandler);
81  ros::NodeHandle nh("~");
82  // Override the default ros sigint handler.
83  // This must be set after the first NodeHandle is created.
84  signal(SIGINT, SigHandler);
85 
86  ros::Publisher pubRobotStop = nh.advertise<dsr_msgs::RobotStop>("/"+ROBOT_ID +ROBOT_MODEL+"/stop",10);
88 
89  //----- create DsrRobot ---------------
90  CDsrRobot robot(nh, my_robot_id, my_robot_model);
91 
92  // run subscriber thread (for monitoring)
93  boost::thread thread_sub(thread_subscriber);
94 
96  float p1[6]={0.0,}; //joint
97  float p2[6]={0.0, 0.0, 90.0, 0.0, 90.0, 0.0}; //joint
98 
99  float x1[6]={400, 500, 800.0, 0.0, 180.0, 0.0}; //task
100  float x2[6]={400, 500, 500.0, 0.0, 180.0, 0.0}; //task
101  float velx[2]={50, 50}; // 태스크 속도를 50(mm/sec), 50(deg/sec)로 설정
102  float accx[2]={100, 100}; // 태스크 가속도를 100(mm/sec2), 100(deg/sec2)로 설정
103 
104 
105  float veljx[6] = {50, 50, 50, 50, 50, 50};
106  float accjx[6] = {100, 100, 100, 100, 100, 100};
107  float fCirclePos[2][6] = {{559,434.5,651.5,0,180,0}, {559,434.5,251.5,0,180,0}};
108 
109  float amp[6] = {10,0,0,0,30,0};
110  float periodic[6] = {1,0,1.5,0,0,0};
111 
112  float fSJPos[3][6] = {{10, -10, 20, -30, 10, 20}, {25, 0, 10, -50, 20, 40}, {50, 50, 50, 50, 50, 50}};
113  float fSXPos[3][6] = {{600, 600, 600, 0, 175, 0},{600, 750, 600, 0, 175, 0},{150, 600, 450, 0, 175, 0}};
114 
115  float bx1[2][6] = {{370, 670, 650, 0, 180, 0}, {370, 670, 650, 0, 180, 0}};
116  float bx2[2][6] = {{370, 670, 400, 0, 180, 0},{370, 545, 400, 0, 180, 0}};
117  float bx3[2][6] = {{370, 595, 400, 0, 180, 0}, {370, 595, 400, 0, 180, 0}};
118 
119  MOVE_POSB posb[3];// = {bx1, 0, 40}, {bx2, 1, 40}, {bx3, 1, 40};
120  for(int i=0; i<2; i++){
121  for(int j=0; j<6; j++){
122  posb[0]._fTargetPos[i][j] = bx1[i][j];
123  }
124  }
125  for(int i=0; i<2; i++){
126  for(int j=0; j<6; j++){
127  posb[1]._fTargetPos[i][j] = bx2[i][j];
128  }
129  }
130  for(int i=0; i<2; i++){
131  for(int j=0; j<6; j++){
132  posb[2]._fTargetPos[i][j] = bx3[i][j];
133  }
134  }
135  posb[0]._iBlendType = 0;
136  posb[1]._iBlendType = 1;
137  posb[2]._iBlendType = 0;
138  posb[0]._fBlendRad = 20;
139  posb[1]._fBlendRad = 20;
140  posb[2]._fBlendRad = 20;
141 
142  while(ros::ok())
143  {
144  robot.movej(p1, 30, 30);
145  robot.movej(p2, 30, 30);
146  robot.movel(x1, velx, accx);
147  robot.movel(x2, velx, accx);
148 
149  robot.movec(fCirclePos, velx, accx);
150  robot.move_periodic(amp, periodic, 0.5, 3, 0);
151  robot.move_spiral(9.5, 20.0, 50.0, velx, accx, 20.0, TASK_AXIS_Z);
152  robot.movesj(fSJPos,3, 30, 100);
153  robot.movesx(fSXPos, 3, velx, accx);
154 
155  robot.moveb(posb, 3, velx, accx);
156 
157  }
158 
159  ROS_INFO("dsr_service_test finished !!!!!!!!!!!!!!!!!!!!!");
160  ROS_INFO("dsr_service_test finished !!!!!!!!!!!!!!!!!!!!!");
161  ROS_INFO("dsr_service_test finished !!!!!!!!!!!!!!!!!!!!!");
162 
164  thread_sub.join();
165 
166  ROS_INFO("dsr_service_test finished !!!!!!!!!!!!!!!!!!!!!");
167  return 0;
168 }
static void thread_subscriber()
float amp[6]
float velx[2]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void SigHandler(int sig)
string ROBOT_ID
float accx[2]
string ROBOT_MODEL
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)
ROSCPP_DECL void shutdown()
void SET_ROBOT(string id, string model)
#define ROS_ERROR(...)


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