navsts2odom.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  Author: Dula Nad
00035  *  Created: 01.02.2013.
00036  *********************************************************************/
00037 #include <labust/tools/conversions.hpp>
00038 
00039 #include <auv_msgs/NavSts.h>
00040 #include <nav_msgs/Odometry.h>
00041 #include <ros/ros.h>
00042 
00043 
00044 void onNavSts(ros::Publisher& odom, const Eigen::Matrix3d& rot, const auv_msgs::NavSts::ConstPtr& msg)
00045 {
00046     nav_msgs::Odometry::Ptr out(new nav_msgs::Odometry());
00047 
00048     out->twist.twist.linear.x = msg->body_velocity.x;
00049     out->twist.twist.linear.y = msg->body_velocity.y;
00050     out->twist.twist.linear.z = msg->body_velocity.z;
00051     out->twist.twist.angular.x = msg->orientation_rate.roll;
00052     out->twist.twist.angular.y = msg->orientation_rate.pitch;
00053     out->twist.twist.angular.z = msg->orientation_rate.yaw;
00054 
00055     Eigen::Vector3d ned;
00056     ned<<msg->position.north, msg->position.east, msg->position.depth;
00057     Eigen::Vector3d xyz = rot*ned;
00058 
00059     out->pose.pose.position.x = xyz(0);
00060     out->pose.pose.position.y = xyz(1);
00061     out->pose.pose.position.z = xyz(2);
00062 
00063     labust::tools::quaternionFromEulerZYX(msg->orientation.roll,
00064                 msg->orientation.pitch,
00065                         msg->orientation.yaw,
00066                         out->pose.pose.orientation);
00067 
00068     odom.publish(out);
00069 }
00070 
00071 
00072 int main(int argc, char* argv[])
00073 {
00074         ros::init(argc,argv,"navsts2odom");
00075         ros::NodeHandle nh, ph("~");
00076 
00077         //Get rotation between the two
00078         std::vector<double> rpy(3,0);
00079         ph.param("rpy",rpy,rpy);
00080 
00081         //Setup the LTP to Odom frame
00082         Eigen::Quaternion<double> q;
00083         labust::tools::quaternionFromEulerZYX(rpy[0], rpy[1], rpy[2],q);
00084         Eigen::Matrix3d rot = q.toRotationMatrix().transpose();
00085 
00086         ros::Publisher odom = nh.advertise<nav_msgs::Odometry>("uwsim_hook", 1);
00087         ros::Subscriber navsts = nh.subscribe<auv_msgs::NavSts>("navsts",1,
00088                         boost::bind(&onNavSts, boost::ref(odom), boost::ref(rot), _1));
00089 
00090         ros::spin();
00091         return 0;
00092 }


labust_sim
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:38