11 #include <boost/thread/thread.hpp> 14 #include "dsr_robot.h" 31 dsr_msgs::Robotiq2FMove srv;
32 srv.request.width = width;
34 if(srvRobotiq2FMove.call(srv))
37 return (srv.response.success);
41 ROS_ERROR(
"Failed to call service dr_control_service : gripper_move\n");
66 ROS_INFO(
"shutdown time! sig=%d",sig);
67 ROS_INFO(
"shutdown time! sig=%d",sig);
68 ROS_INFO(
"shutdown time! sig=%d",sig);
74 dsr_msgs::RobotStop msg;
76 msg.stop_mode = STOP_TYPE_QUICK;
77 pubRobotStop.publish(msg);
82 int main(
int argc,
char** argv)
85 string my_robot_id =
"dsr01";
86 string my_robot_model =
"m1013";
88 ROS_INFO(
"default arguments: dsr01 m1013");
92 ROS_ERROR(
"invalid arguments: <ns> <model> (ex) dsr01 m1013");
95 for (
int i = 1; i < argc; i++){
96 printf(
"argv[%d] = %s\n", i, argv[i]);
98 my_robot_id = argv[1];
99 my_robot_model = argv[2];
114 CDsrRobot robot(nh, my_robot_id, my_robot_model);
120 float p0[6]={0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
121 float p1[6]={0.0, 0.0, 90.0, 0.0, 90.0 , 0.0};
122 float p2[6]={180.0, 0.0, 90, 0.0, 90.0, 0.0};
124 float x1[6]={0, 0, -200, 0, 0, 0};
125 float x2[6]={0, 0, 200, 0, 0, 0};
126 float velx[2]={50, 50};
127 float accx[2]={100, 100};
131 robot.movej(p0, 60, 30);
132 robot.movej(p1, 60, 30);
134 robot.movel(x1, velx, accx, 2, 0.
f, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE);
137 robot.movel(x2, velx, accx, 2, 0.
f, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE);
139 robot.movej(p2, 60, 30, 3);
140 robot.movel(x1, velx, accx, 2, 0.
f, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE);
143 robot.movel(x2, velx, accx, 2, 0.
f, MOVE_REFERENCE_BASE, MOVE_MODE_RELATIVE);
146 ROS_INFO(
"object_pick_and_place_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
147 ROS_INFO(
"object_pick_and_place_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
148 ROS_INFO(
"object_pick_and_place_simple_cpp finished !!!!!!!!!!!!!!!!!!!!!");
153 ROS_INFO(
"object_pick_and_place_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)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void shutdown()
int main(int argc, char **argv)
int gripper_move(float width)
static void thread_subscriber()