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


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