USBLSim.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * USBLSim.cpp
00003  *
00004  *  Created on: Mar 2, 2015
00005  *      Author: Filip Mandic
00006  *
00007  ********************************************************************/
00008 
00009 /*********************************************************************
00010  * Software License Agreement (BSD License)
00011  *
00012  *  Copyright (c) 2015, LABUST, UNIZG-FER
00013  *  All rights reserved.
00014  *
00015  *  Redistribution and use in source and binary forms, with or without
00016  *  modification, are permitted provided that the following conditions
00017  *  are met:
00018  *
00019  *   * Redistributions of source code must retain the above copyright
00020  *     notice, this list of conditions and the following disclaimer.
00021  *   * Redistributions in binary form must reproduce the above
00022  *     copyright notice, this list of conditions and the following
00023  *     disclaimer in the documentation and/or other materials provided
00024  *     with the distribution.
00025  *   * Neither the name of the LABUST nor the names of its
00026  *     contributors may be used to endorse or promote products derived
00027  *     from this software without specific prior written permission.
00028  *
00029  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00030  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00031  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00032  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00033  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00034  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00035  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00036  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00037  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00038  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00039  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00040  *  POSSIBILITY OF SUCH DAMAGE.
00041  *
00042  *********************************************************************/
00043 #include <Eigen/Dense>
00044 #include <ros/ros.h>
00045 #include <auv_msgs/NavSts.h>
00046 #include <std_msgs/Float32.h>
00047 #include <underwater_msgs/USBLFix.h>
00048 #include <labust/math/NumberManipulation.hpp>
00049 
00050 class USBLSim{
00051 
00052 public:
00053 
00054         USBLSim(){
00055 
00056                 ros::NodeHandle nh;
00057 
00058                 subVehiclePos = nh.subscribe<auv_msgs::NavSts>("pos_first",1,&USBLSim::onVehiclePos,this);
00059                 subTargetPos = nh.subscribe<auv_msgs::NavSts>("pos_second",1,&USBLSim::onTargetPos,this);
00060                 pubUSBLFix = nh.advertise<underwater_msgs::USBLFix>("usbl_fix",1);
00061                 pubRange = nh.advertise<std_msgs::Float32>("range",1);
00062 
00063         }
00064 
00065         ~USBLSim(){}
00066 
00067         void start(){
00068 
00069                 ros::NodeHandle ph("~");
00070                 double Ts(1.0);
00071                 ph.param("Trange",Ts,Ts);
00072                 ros::Rate rate(1/Ts);
00073 
00074                 int i = 0;
00075 
00076                 while (ros::ok()){
00077 
00078 
00079                         if(i++==0) continue;
00080                         range = (vehPos-tarPos).norm();
00081                         bearing = labust::math::wrapRad(std::atan2(double(vehPos(1)-tarPos(1)),double(vehPos(0)-tarPos(0)))-0*vehYaw);
00082                         elevation = std::asin((double(vehPos(2)-tarPos(2)))/range);
00083 
00084 
00085                         usbl.header.stamp = ros::Time::now();
00086                         usbl.range = range;
00087                         usbl.bearing = bearing;
00088                         usbl.elevation = elevation;
00089 
00090                         std_msgs::Float32 range;
00091                         range.data = usbl_past.range;
00092                         pubRange.publish(range);
00093 
00094                         pubUSBLFix.publish(usbl_past);
00095 
00096                         usbl_past = usbl;
00097 
00098 
00099                         rate.sleep();
00100                         ros::spinOnce();
00101                 }
00102         }
00103 
00104         void onVehiclePos(const auv_msgs::NavSts::ConstPtr& data){
00105 
00106                 vehPos << data->position.north, data->position.east, data->position.depth;
00107                 vehYaw = data->orientation.yaw;
00108         }
00109 
00110         void onTargetPos(const auv_msgs::NavSts::ConstPtr& data){
00111 
00112                 tarPos << data->position.north, data->position.east, data->position.depth;
00113         }
00114 
00115         /*
00116          * Class variables
00117          */
00118 
00119         ros::Subscriber subVehiclePos, subTargetPos;
00120         ros::Publisher pubUSBLFix, pubRange;
00121 
00122         Eigen::Vector3d vehPos, tarPos;
00123         double vehYaw;
00124         //std_msgs::Float32 range, bearing, elevation;
00125         double range, bearing, elevation;
00126 
00127 
00128 
00129         underwater_msgs::USBLFix usbl, usbl_past;
00130 };
00131 
00132 int main(int argc, char* argv[])
00133 {
00134         ros::init(argc,argv,"range_sim");
00135         USBLSim usblSim;
00136         usblSim.start();
00137         return 0;
00138 }
00139 
00140 
00141 
00142 
00143 
00144 
00145 
00146 
00147 
00148 
00149 
00150 


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