// it's for Latex

pages

[Pick and Place using Inception_v3 in ROS] #03. Making open_manipulator_play_recorded_trajectory node

#02까지는 Manipulator의 trajectory를 recording 하는 소스코드를 구현하였다.
#03에서는 인식된 Object에 따라서 각각의 Trajectory를 수행하도록 할 것이다.



PC Enviroment ( Labtop )
OS : Ubuntu 16.04
ROS : Kinetic
CPU : i8
Graphic Card : RTX 2070

Hardware
OpenManipulator(ROBOTIS)
U2D2 Interface

Software
Inception_v3



정신없이 진행되어서 소스만 일단 올리겠다.

작업한 내용은 다음과 같다.

1. 기본적으로 텍스트파일을 읽어서 Object 별로 Trajectory를 얻는다.
#02에서 진행한 text parsing 기법 이용.


2. OpenManipulator Class에 Subscriber를 만든다.
http://wiki.ros.org/roscpp_tutorials/Tutorials/UsingClassMethodsAsCallbacks


3. ros_inception_v3 node 로부터 result 받기.
https://suho0515.blogspot.com/2019/10/tensorflow-image-recognition-in-ros-01.html

#01 ~ #04
참고로 publish되는 massege는 /open_manipulator/result로 변경해야 한다.


4. 해당 노드는 서비스 기능만 수행할 것이고, 서비스를 controller에 전달할 것이다.
그러므로 slave와 통신되는 관련 내용들을 지워준다.


아래는 해당 코드다.
CmakeLists 와 Launch 파일은 #02에서와 같이 진행한다.


1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
/*******************************************************************************
* Copyright 2018 ROBOTIS CO., LTD.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
*     http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*******************************************************************************/
/* Authors: Darby Lim, Hye-Jong KIM, Ryan Shim, Yong-Ho Na */
#include "open_manipulator_master_slave/open_manipulator_master.h"
#include <fstream>
#include <iostream>
#include <string>
#include <sstream>
using namespace std;
OpenManipulatorMaster::OpenManipulatorMaster(std::string usb_port, std::string baud_rate)
    :node_handle_(""),
     priv_node_handle_("~"),
     service_call_period_(0.01),
     mode_state_(MASTER_SLAVE_MODE),
     buffer_index_(0),
     obj("")
{
  service_call_period_  = priv_node_handle_.param<double>("service_call_period"0.010f);
  dxl_id_.push_back(priv_node_handle_.param<int32_t>("joint1_id"1));
  dxl_id_.push_back(priv_node_handle_.param<int32_t>("joint2_id"2));
  dxl_id_.push_back(priv_node_handle_.param<int32_t>("joint3_id"3));
  dxl_id_.push_back(priv_node_handle_.param<int32_t>("joint4_id"4));
  dxl_id_.push_back(priv_node_handle_.param<int32_t>("gripper_id"5));
  goal_joint_position_.resize(NUM_OF_JOINT);
  goal_tool_position_ = 0.0;
  initOpenManipulator(usb_port, baud_rate, service_call_period_);
  initServiceClient();
}
OpenManipulatorMaster::~OpenManipulatorMaster()
{
  delete actuator_;
  delete tool_;
  if(ros::isStarted()) {
    ros::shutdown();
    ros::waitForShutdown();
  }
}
void OpenManipulatorMaster::initServiceClient()
{
  goal_joint_space_path_client_ = node_handle_.serviceClient<open_manipulator_msgs::SetJointPosition>("goal_joint_space_path");
  goal_tool_control_client_ = node_handle_.serviceClient<open_manipulator_msgs::SetJointPosition>("goal_tool_control");
}
void OpenManipulatorMaster::initOpenManipulator(STRING usb_port, STRING baud_rate, double service_call_period)
{
  /*****************************************************************************
  ** Initialize Manipulator Parameter
  *****************************************************************************/
  addWorld("world",   // world name
           "joint1"); // child name
  addJoint("joint1",  // my name
           "world",   // parent name
           "joint2",  // child name
           math::vector3(0.0120.00.017),                // relative position
           math::convertRPYToRotationMatrix(0.00.00.0), // relative orientation
           Z_AXIS,        // axis of rotation
           dxl_id_.at(0), // actuator id
           M_PI,          // max joint limit (3.14 rad)
           -M_PI);        // min joint limit (-3.14 rad)
  addJoint("joint2",  // my name
           "joint1",  // parent name
           "joint3",  // child name
           math::vector3(0.00.00.0595),                 // relative position
           math::convertRPYToRotationMatrix(0.00.00.0), // relative orientation
           Y_AXIS,        // axis of rotation
           dxl_id_.at(1), // actuator id
           M_PI_2,        // max joint limit (1.67 rad)
           -2.05);        // min joint limit (-2.05 rad)
  addJoint("joint3",  // my name
           "joint2",  // parent name
           "joint4",  // child name
           math::vector3(0.0240.00.128),                // relative position
           math::convertRPYToRotationMatrix(0.00.00.0), // relative orientation
           Y_AXIS,        // axis of rotation
           dxl_id_.at(2), // actuator id
           1.53,          // max joint limit (1.53 rad)
           -M_PI_2);      // min joint limit (-1.67 rad)
  addJoint("joint4",  // my name
           "joint3",  // parent name
           "gripper"// child name
           math::vector3(0.1240.00.0),                  // relative position
           math::convertRPYToRotationMatrix(0.00.00.0), // relative orientation
           Y_AXIS,        // axis of rotation
           dxl_id_.at(3), // actuator id
           2.0,           // max joint limit (2.0 rad)
           -1.8);         // min joint limit (-1.8 rad)
  addTool("gripper",  // my name
          "joint4",   // parent name
          math::vector3(0.1260.00.0),                  // relative position
          math::convertRPYToRotationMatrix(0.00.00.0), // relative orientation
          dxl_id_.at(4),  // actuator id
          0.010,          // max gripper limit (0.01 m)
          -0.010,         // min gripper limit (-0.01 m)
          -0.015);        // Change unit from `meter` to `radian`
  /*****************************************************************************
  ** Parsing txt File
  *****************************************************************************/
  // for Reading File  
  string filePath = "/tmp/glue.txt";
  ifstream openFile_glue(filePath.data());
  if(openFile_glue.is_open())
  {
    string line;
    record_buffer_glue_.clear();
    
    while(getline(openFile_glue, line)){
      //cout << line << endl;
      // Parsing text data to record_buffer_
      
      istringstream iss(line);
      WaypointBuffer temp;
      std::vector<double> goal_joint_position_;
      double goal_tool_position_;
      goal_joint_position_.resize(NUM_OF_JOINT);
      goal_tool_position_ = 0.0;
      int count = 0;
      do
      {
        string sub;
        iss >> sub;
        //cout << "Substring: " << sub << endl;
      
        if(count==0) goal_joint_position_.at(0= stod(sub);
        else if(count==1) goal_joint_position_.at(1= stod(sub);
        else if(count==2) goal_joint_position_.at(2= stod(sub);
        else if(count==3) goal_joint_position_.at(3= stod(sub);
        else if(count==4) goal_tool_position_ = stod(sub);
        temp.joint_angle = goal_joint_position_;
        temp.tool_position = goal_tool_position_;
        
        count++;
      } while (iss);
      record_buffer_glue_.push_back(temp);
    }
    openFile_glue.close();
  }
  // for Reading File  
  filePath = "/tmp/eclipse.txt";
  ifstream openFile_eclipse(filePath.data());
  if(openFile_eclipse.is_open())
  {
    string line;
    record_buffer_eclipse_.clear();
    
    while(getline(openFile_eclipse, line)){
      //cout << line << endl;
      // Parsing text data to record_buffer_
      
      istringstream iss(line);
      WaypointBuffer temp;
      std::vector<double> goal_joint_position_;
      double goal_tool_position_;
      goal_joint_position_.resize(NUM_OF_JOINT);
      goal_tool_position_ = 0.0;
      int count = 0;
      do
      {
        string sub;
        iss >> sub;
        //cout << "Substring: " << sub << endl;
      
        if(count==0) goal_joint_position_.at(0= stod(sub);
        else if(count==1) goal_joint_position_.at(1= stod(sub);
        else if(count==2) goal_joint_position_.at(2= stod(sub);
        else if(count==3) goal_joint_position_.at(3= stod(sub);
        else if(count==4) goal_tool_position_ = stod(sub);
        temp.joint_angle = goal_joint_position_;
        temp.tool_position = goal_tool_position_;
        
        count++;
      } while (iss);
      record_buffer_eclipse_.push_back(temp);
    }
    openFile_eclipse.close();
  }
}
bool OpenManipulatorMaster::setJointSpacePath(double path_time, std::vector<double> set_goal_joint_position)
{
  auto joint_name = getManipulator()->getAllActiveJointComponentName();
  std::vector<double> joint_value;
  if(set_goal_joint_position.size())  {
    joint_value = set_goal_joint_position;
  }
  else
  {
    joint_value.push_back(record_buffer_.at(0).joint_angle.at(0));
    joint_value.push_back(record_buffer_.at(0).joint_angle.at(1));
    joint_value.push_back(record_buffer_.at(0).joint_angle.at(2));
    joint_value.push_back(record_buffer_.at(0).joint_angle.at(3));
  }
  open_manipulator_msgs::SetJointPosition srv;
  srv.request.joint_position.joint_name = joint_name;
  for(int i = 0; i < NUM_OF_JOINT; i ++)
  {
    if(getManipulator()->checkJointLimit(joint_name.at(i), joint_value.at(i)))
      srv.request.joint_position.position.push_back(joint_value.at(i));
    else
      srv.request.joint_position.position.push_back(goal_joint_position_.at(i));
  }
  goal_joint_position_ = srv.request.joint_position.position;
  srv.request.path_time = path_time;
  if(goal_joint_space_path_client_.call(srv))
  {
    return srv.response.is_planned;
  }
  return false;
}
bool OpenManipulatorMaster::setToolPath(double set_goal_tool_position)
{
  double tool_value;
  if(set_goal_tool_position < -0.1)
    tool_value = record_buffer_.at(0).tool_position;
  else
    tool_value = set_goal_tool_position;
  open_manipulator_msgs::SetJointPosition srv;
  srv.request.joint_position.joint_name.push_back("gripper");
  if(getManipulator()->checkJointLimit("gripper", tool_value))
    srv.request.joint_position.position.push_back(tool_value);
  else
    srv.request.joint_position.position.push_back(goal_tool_position_);
  goal_tool_position_ = srv.request.joint_position.position.at(0);
  if(goal_tool_control_client_.call(srv))
  {
    return srv.response.is_planned;
  }
  return false;
}
void OpenManipulatorMaster::publishCallback(const ros::TimerEvent&)
{
  static int count = 0;
  if(!(count % 5))
  {
    printText();
    if(kbhit())
      setModeState(std::getchar());
  }
  count ++;
  receiveAllJointActuatorValue();
  receiveAllToolActuatorValue();
  if(mode_state_ == PLAY_RECORDED_TRAJECTORY_MODE)
  {
    if(record_buffer_.size() > buffer_index_)
    {
      setJointSpacePath(service_call_period_, record_buffer_.at(buffer_index_).joint_angle);
      setToolPath(record_buffer_.at(buffer_index_).tool_position);
      buffer_index_ ++;
    }
  }
}
void OpenManipulatorMaster::setModeState(char ch)
{
  if(ch == '1')
  {
    buffer_index_ = 0;
    if(obj == "glue") record_buffer_ = record_buffer_glue_;
    else if(obj == "eclipse") record_buffer_ = record_buffer_eclipse_;
    if(record_buffer_.size()) {
      double sync_path_time = 1.0;
      receiveAllJointActuatorValue();
      receiveAllToolActuatorValue();
      setJointSpacePath(sync_path_time);
      setToolPath();
      ros::WallDuration sleep_time(sync_path_time);
      sleep_time.sleep();
    }
    mode_state_ = PLAY_RECORDED_TRAJECTORY_MODE;
  }
}
void OpenManipulatorMaster::printText()
{
  system("clear");
  printf("\n");
  printf("-----------------------------\n");
  printf("Control Your OpenManipulator!\n");
  printf("-----------------------------\n");
  printf("Present Control Mode\n");
  
  if(mode_state_ == PLAY_RECORDED_TRAJECTORY_MODE)
  {
    printf("Play Recorded Trajectory Mode\n");
    printf("Buffer Size : %d\n", (int)(record_buffer_.size()));
    printf("Buffer index : %d\n", buffer_index_);
  }
  printf("-----------------------------\n");
  printf("1 : Play Recorded Trajectory\n");
  printf("-----------------------------\n");
  printf("Present Joint Angle J1: %.3lf J2: %.3lf J3: %.3lf J4: %.3lf\n",
         goal_joint_position_.at(0),
         goal_joint_position_.at(1),
         goal_joint_position_.at(2),
         goal_joint_position_.at(3));
  printf("Present Tool Position: %.3lf\n", goal_tool_position_);
  printf("-----------------------------\n");
}
bool OpenManipulatorMaster::kbhit()
{
  termios term;
  tcgetattr(0&term);
  termios term2 = term;
  term2.c_lflag &= ~ICANON;
  tcsetattr(0, TCSANOW, &term2);
  int byteswaiting;
  ioctl(0, FIONREAD, &byteswaiting);
  tcsetattr(0, TCSANOW, &term);
  return byteswaiting > 0;
}
// custom by suho, for result callback
void OpenManipulatorMaster::resultCallback(const std_msgs::String::ConstPtr& msg)
{
  ROS_INFO("I heard: [%s]", msg->data.c_str());
  obj = msg->data.c_str();
}
int main(int argc, char **argv)
{
  // Init ROS node
  ros::init(argc, argv, "open_manipulator_play_recorded_trajectory");
  ros::NodeHandle node_handle("");
  
  std::string usb_port = "/dev/ttyUSB0";
  std::string baud_rate = "1000000";
  if (argc < 3)
  {
    log::error("Please set '-port_name' and  '-baud_rate' arguments for connected Dynamixels");
    return 0;
  }
  else
  {
    usb_port = argv[1];
    baud_rate = argv[2];
  }
  OpenManipulatorMaster open_manipulator_master(usb_port, baud_rate);
  ros::Timer publish_timer = node_handle.createTimer(ros::Duration(open_manipulator_master.getServiceCallPeriod()), &OpenManipulatorMaster::publishCallback, &open_manipulator_master);
  ros::NodeHandle nh;
  ros::Subscriber open_manipulator_sub = nh.subscribe("result"100&OpenManipulatorMaster::resultCallback,&open_manipulator_master);
  
  while (ros::ok())
  {
     ros::spinOnce();
  }
  return 0;
}
cs





























댓글 4개:

  1. 안녕하세요! 블로그 글 보고 해결되지 않는 부분때매 연락드립니다 ㅠ
    2. OpenManipulator Class에 Subscriber를 만든다.
    이 부분의 코드는 서비스를 Subscribe 하는 건가요? 어떤 서비스를 받는거죠?

    답글삭제
    답글
    1. 제가 블로거를 티스토리로 옮긴지 꽤 되서 이제 확인했네요 ㅠ 아직 알아보고 계신 내용이라면 확인해보고 답변드리겠습니다. :)

      삭제
  2. Image label을 result로 받는 부분을 키보드 입력으로 변경했습니다.
    그러나 filePath를 읽어오지 못하 부분을 해결하지 못했습니다.
    도움을 청하고자 합니다. 메일을 주고받을 수 있을까요 ??

    답글삭제