Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
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
00117
00118
00119 ros::Subscriber subVehiclePos, subTargetPos;
00120 ros::Publisher pubUSBLFix, pubRange;
00121
00122 Eigen::Vector3d vehPos, tarPos;
00123 double vehYaw;
00124
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