range_sim.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * range_sim.cpp
00003  *
00004  *  Created on: Aug 18, 2014
00005  *      Author: Filip Mandic
00006  *
00007  ********************************************************************/
00008 
00009 /*********************************************************************
00010  * Software License Agreement (BSD License)
00011  *
00012  *  Copyright (c) 2010, 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 
00048 class RangeSim{
00049 
00050 public:
00051 
00052         RangeSim(){
00053 
00054                 ros::NodeHandle nh;
00055 
00056                 vehiclePosSub = nh.subscribe<auv_msgs::NavSts>("meas_ideal",1,&RangeSim::onVehiclePos,this);
00057                 targetPosSub = nh.subscribe<auv_msgs::NavSts>("target_pos",1,&RangeSim::onTargetPos,this);
00058                 rangeMeas = nh.advertise<std_msgs::Float32>("rangeMeas",1);
00059         }
00060 
00061         ~RangeSim(){}
00062 
00063         void start(){
00064 
00065                 ros::NodeHandle ph("~");
00066                 double Ts(1.0);
00067                 ph.param("Trange",Ts,Ts);
00068                 ros::Rate rate(1/Ts);
00069 
00070                 while (ros::ok())
00071                 {
00072 
00073                         range.data = (vehPos-tarPos).norm();
00074                         rangeMeas.publish(range);
00075 
00076                         rate.sleep();
00077                         ros::spinOnce();
00078 
00079                 }
00080         }
00081 
00082         void onVehiclePos(const auv_msgs::NavSts::ConstPtr& data){
00083 
00084                 vehPos << data->position.north, data->position.east, data->position.depth;
00085         }
00086 
00087         void onTargetPos(const auv_msgs::NavSts::ConstPtr& data){
00088 
00089                 tarPos << data->position.north, data->position.east, data->position.depth;
00090         }
00091 
00092         /*
00093          * Class variables
00094          */
00095 
00096         ros::Subscriber vehiclePosSub, targetPosSub;
00097         ros::Publisher rangeMeas;
00098 
00099         Eigen::Vector3d vehPos, tarPos;
00100         std_msgs::Float32 range;
00101 };
00102 
00103 int main(int argc, char* argv[])
00104 {
00105         ros::init(argc,argv,"range_sim");
00106         RangeSim rs;
00107         rs.start();
00108         return 0;
00109 }
00110 
00111 
00112 
00113 
00114 
00115 
00116 


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