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 #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
00078 std::vector<double> rpy(3,0);
00079 ph.param("rpy",rpy,rpy);
00080
00081
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 }