DvlSim.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 <nav_msgs/Odometry.h>
00040 #include <geometry_msgs/TwistStamped.h>
00041 #include <std_msgs/Float32.h>
00042 #include <ros/ros.h>
00043 
00044 #include <Eigen/Dense>
00045 
00046 struct DvlSim
00047 {
00048         DvlSim():
00049                 maxBottomLock(100),
00050                 maxDepth(100),
00051                 dvl_pub(1)
00052         {
00053                 ros::NodeHandle nh,ph("~");
00054 
00055                 ph.param("MaxBottomLock",maxBottomLock, maxBottomLock);
00056                 ph.param("MaxDepth", maxDepth, maxDepth);
00057                 ph.param("DvlPub", dvl_pub, dvl_pub);
00058 
00059                 odom = nh.subscribe<nav_msgs::Odometry>("meas_odom",1,&DvlSim::onOdom, this);
00060                 dvl_nu = nh.advertise<geometry_msgs::TwistStamped>("dvl",1);
00061                 dvl_ned = nh.advertise<geometry_msgs::TwistStamped>("dvl_ned",1);
00062                 altitude_pub = nh.advertise<std_msgs::Float32>("altitude",1);
00063 
00064                 last_pos[0] = last_pos[1] = last_pos[2] = 0;
00065         }
00066 
00067         void onOdom(const typename nav_msgs::Odometry::ConstPtr& msg)
00068         {
00069                 static int i=0;
00070                 i=++i%dvl_pub;
00071 
00072                 if (i == 0)
00073                 {
00074                         double dT = (ros::Time::now() - lastTime).toSec();
00075                         lastTime = ros::Time::now();
00076                         geometry_msgs::TwistStamped::Ptr dvl(new geometry_msgs::TwistStamped());
00077                         dvl->header.stamp = ros::Time::now();
00078                         dvl->header.frame_id = msg->header.frame_id;
00079                         double pos[3],v[3];
00080                         labust::tools::pointToVector(msg->pose.pose.position, pos);
00081                         for (int i=0; i<3; ++i)
00082                         {
00083                                 v[i] = (pos[i] - last_pos[i])/dT;
00084                                 last_pos[i] = pos[i];
00085                         }
00086                         labust::tools::vectorToPoint(v, dvl->twist.linear);
00087                         dvl_ned.publish(dvl);
00088 
00089                         dvl.reset(new geometry_msgs::TwistStamped());
00090                         dvl->header.stamp = ros::Time::now();
00091                         dvl->header.frame_id = msg->child_frame_id;
00092                         //Calculate body-fixed speeds
00093                         Eigen::Quaternion<double> q(msg->pose.pose.orientation.w,
00094                                         msg->pose.pose.orientation.x,
00095                                         msg->pose.pose.orientation.y,
00096                                         msg->pose.pose.orientation.z);
00097                         Eigen::Vector3d nu = q.matrix().transpose() * Eigen::Vector3d(v[0],v[1],v[2]);
00098                         dvl->twist.linear.x = nu(0);
00099                         dvl->twist.linear.y = nu(1);
00100                         dvl->twist.linear.z = nu(2);
00101                         dvl_nu.publish(dvl);
00102 
00103                         if ((maxDepth - msg->pose.pose.position.z) < maxBottomLock)
00104                         {
00105                                 std_msgs::Float32::Ptr altitude(new std_msgs::Float32());
00106                                 altitude->data = maxDepth - msg->pose.pose.position.z;
00107                                 altitude_pub.publish(altitude);
00108                         }
00109                 }
00110         }
00111 
00112 private:
00113         ros::Subscriber odom;
00114         ros::Publisher dvl_nu, altitude_pub, dvl_ned;
00115         ros::Time lastTime;
00116         double last_pos[3];
00117         int dvl_pub;
00118         double maxBottomLock, maxDepth;
00119 };
00120 
00121 int main(int argc, char* argv[])
00122 {
00123         ros::init(argc,argv,"dvl_sim");
00124         ros::NodeHandle nh;
00125         DvlSim dvl;
00126         ros::spin();
00127         return 0;
00128 }
00129 
00130 


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