setVehiclePosition.cpp
Go to the documentation of this file.
00001 /* 
00002  * Copyright (c) 2013 University of Jaume-I.
00003  * All rights reserved. This program and the accompanying materials
00004  * are made available under the terms of the GNU Public License v3.0
00005  * which accompanies this distribution, and is available at
00006  * http://www.gnu.org/licenses/gpl.html
00007  * 
00008  * Contributors:
00009  *     Mario Prats
00010  *     Javier Perez
00011  */ 
00012 
00013 #include <stdlib.h>
00014 #include <string.h>
00015 
00016 //ROS
00017 #include <ros/ros.h>
00018 #include <nav_msgs/Odometry.h>
00019 #include <osg/Quat>
00020 #include <osg/Vec3d>
00021 #include <osg/Matrix>
00022 
00023 int main(int argc, char **argv) {
00024 
00025         ros::init(argc, argv, "setVehiclePosition");
00026         ros::NodeHandle nh;
00027 
00028         if (argc!=8) {
00029                 std::cerr << "USAGE: " << argv[0] << " <topic> <x> <y> <z> <roll> <pitch> <yaw>" << std::endl;
00030                 std::cerr << "units in meters and radians" << std::endl;
00031                 return 0;
00032         }       
00033 
00034         std::string topic(argv[1]);
00035         double x=atof(argv[2]);
00036         double y=atof(argv[3]);
00037         double z=atof(argv[4]);
00038         double roll=atof(argv[5]);
00039         double pitch=atof(argv[6]);
00040         double yaw=atof(argv[7]);
00041 
00042         ros::Publisher position_pub;
00043         position_pub=nh.advertise<nav_msgs::Odometry>(topic,1);
00044 
00045         osg::Matrixd T, Rx, Ry, Rz, transform;
00046         T.makeTranslate(x,y,z);
00047         Rx.makeRotate(roll,1,0,0);
00048         Ry.makeRotate(pitch,0,1,0);
00049         Rz.makeRotate(yaw,0,0,1);
00050         transform=Rz*Ry*Rx*T;
00051         osg::Vec3d trans=transform.getTrans();
00052         osg::Quat rot=transform.getRotate();
00053 
00054         ros::Rate r(10);
00055         while (ros::ok()) {
00056                 nav_msgs::Odometry odom;
00057                 odom.pose.pose.position.x=trans.x();
00058                 odom.pose.pose.position.y=trans.y();
00059                 odom.pose.pose.position.z=trans.z();
00060                 odom.pose.pose.orientation.x=rot.x();
00061                 odom.pose.pose.orientation.y=rot.y();
00062                 odom.pose.pose.orientation.z=rot.z();
00063                 odom.pose.pose.orientation.w=rot.w();
00064 
00065                 odom.twist.twist.linear.x=0;
00066                 odom.twist.twist.linear.y=0;
00067                 odom.twist.twist.linear.z=0;
00068                 odom.twist.twist.angular.x=0;
00069                 odom.twist.twist.angular.y=0;
00070                 odom.twist.twist.angular.z=0;
00071                 for (int i=0; i<36; i++) {
00072                         odom.twist.covariance[i]=0;
00073                         odom.pose.covariance[i]=0;
00074                 }
00075                 position_pub.publish(odom);
00076 
00077                 ros::spinOnce();
00078                 r.sleep();
00079         }
00080 
00081         return 0;
00082 }


uwsim
Author(s): Mario Prats , Javier Perez
autogenerated on Fri Aug 28 2015 13:28:58