Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include "geometry_msgs/Pose.h"
00003 #include "iri_wam_common_msgs/pose_move.h"
00004
00005 int main(int argc, char** argv)
00006 {
00007
00008 ros::init(argc, argv, "robot_driver");
00009
00010 if (argc != 11) {
00011 std::cerr << "Usage: " << argv[0]
00012 << " /wrapper/pose_move pos.x pos.y. pos.z quat.x quat.y quat.z quat.w vel acc (vel recomended 0.1) (acc recomended 0.2)" << std::endl;
00013 return 1;
00014 }
00015
00016 iri_wam_common_msgs::pose_move pose_srv;
00017
00018 int p = 2;
00019 pose_srv.request.pose.position.x = atof(argv[p]);
00020 pose_srv.request.pose.position.y = atof(argv[p+1]);
00021 pose_srv.request.pose.position.z = atof(argv[p+2]);
00022 pose_srv.request.pose.orientation.x = atof(argv[p+3]);
00023 pose_srv.request.pose.orientation.y = atof(argv[p+4]);
00024 pose_srv.request.pose.orientation.y = atof(argv[p+5]);
00025 pose_srv.request.pose.orientation.z = atof(argv[p+6]);
00026 pose_srv.request.vel = atof(argv[p+7]);
00027 pose_srv.request.acc = atof(argv[p+8]);
00028
00029 if (ros::service::call(argv[1], pose_srv))
00030 {
00031 std::cout << "Move done" << std::endl;
00032 }
00033
00034 return 0;
00035 }