11 #include <boost/thread/thread.hpp> 14 #include "dsr_robot.h" 42 ROS_INFO(
"shutdown time! sig=%d",sig);
43 ROS_INFO(
"shutdown time! sig=%d",sig);
44 ROS_INFO(
"shutdown time! sig=%d",sig);
50 dsr_msgs::RobotStop msg;
52 msg.stop_mode = STOP_TYPE_QUICK;
53 pubRobotStop.publish(msg);
58 int main(
int argc,
char** argv)
61 string my_robot_id =
"dsr01";
62 string my_robot_model =
"m1013";
64 ROS_INFO(
"default arguments: dsr01 m1013");
68 ROS_ERROR(
"invalid arguments: <ns> <model> (ex) dsr01 m1013");
71 for (
int i = 1; i < argc; i++){
72 printf(
"argv[%d] = %s\n", i, argv[i]);
74 my_robot_id = argv[1];
75 my_robot_model = argv[2];
90 CDsrRobot robot(nh, my_robot_id, my_robot_model);
97 float p2[6]={0.0, 0.0, 90.0, 0.0, 90.0, 0.0};
99 float x1[6]={400, 500, 800.0, 0.0, 180.0, 0.0};
100 float x2[6]={400, 500, 500.0, 0.0, 180.0, 0.0};
101 float velx[2]={50, 50};
102 float accx[2]={100, 100};
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}};
109 float amp[6] = {10,0,0,0,30,0};
110 float periodic[6] = {1,0,1.5,0,0,0};
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}};
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}};
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];
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];
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];
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;
144 robot.movej(p1, 30, 30);
145 robot.movej(p2, 30, 30);
146 robot.movel(x1, velx, accx);
147 robot.movel(x2, velx, accx);
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);
155 robot.moveb(posb, 3, velx, accx);
159 ROS_INFO(
"single_robot_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
160 ROS_INFO(
"single_robot_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
161 ROS_INFO(
"single_robot_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
166 ROS_INFO(
"single_robot_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void SET_ROBOT(string id, string model)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static void thread_subscriber()
ROSCPP_DECL void shutdown()