10 #include <geometry_msgs/Twist.h> 15 #include "dsr_robot.h" 31 ros::Publisher pubMobile = node->advertise<geometry_msgs::Twist>(
"/"+
ROBOT_ID+
"/twist_marker_server/cmd_vel", 1000);
34 geometry_msgs::Twist msg;
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);
55 ROS_INFO(
"shutdown time! sig=%d",sig);
56 ROS_INFO(
"shutdown time! sig=%d",sig);
57 ROS_INFO(
"shutdown time! sig=%d",sig);
63 dsr_msgs::RobotStop msg;
65 msg.stop_mode = STOP_TYPE_QUICK;
66 pubRobotStop.publish(msg);
71 int main(
int argc,
char** argv)
74 const string my_robot_id =
"dsr01";
75 const string my_robot_model =
"m1013";
89 CDsrRobot robot(nh, my_robot_id, my_robot_model);
96 float p2[6]={0.0, 0.0, 90.0, 0.0, 90.0, 0.0};
98 float x1[6]={400, 500, 800.0, 0.0, 180.0, 0.0};
99 float x2[6]={400, 500, 500.0, 0.0, 180.0, 0.0};
100 float velx[2]={50, 50};
101 float accx[2]={100, 100};
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}};
108 float amp[6] = {10,0,0,0,30,0};
109 float periodic[6] = {1,0,1.5,0,0,0};
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}};
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}};
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];
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];
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];
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;
143 robot.movej(p1, 30, 30);
144 robot.movej(p2, 30, 30);
145 robot.movel(x1, velx, accx);
146 robot.movel(x2, velx, accx);
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);
154 robot.moveb(posb, 3, velx, accx);
158 ROS_INFO(
"single_robot_mobile_cpp finished !!!!!!!!!!!!!!!!!!!!!");
159 ROS_INFO(
"single_robot_mobile_cpp finished !!!!!!!!!!!!!!!!!!!!!");
160 ROS_INFO(
"single_robot_mobile_cpp finished !!!!!!!!!!!!!!!!!!!!!");
165 ROS_INFO(
"single_robot_mobile_cpp finished !!!!!!!!!!!!!!!!!!!!!");
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static void thread_mobile()
void SET_ROBOT(string id, string model)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void shutdown()