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
00032 #include <sensor_msgs/Imu.h>
00033 #include "geometry_msgs/Vector3Stamped.h"
00034 #include "geometry_msgs/QuaternionStamped.h"
00035
00036 #include "geometry_msgs/Pose.h"
00037 #include <sensor_msgs/JointState.h>
00038 #include <tf/transform_listener.h>
00039 #include <nav_msgs/Odometry.h>
00040 #include "geometry_msgs/Pose.h"
00041 #include "geometry_msgs/Quaternion.h"
00042 #include "tf/transform_datatypes.h"
00043 #include <stdio.h>
00044 #include <std_msgs/Float64.h>
00045 #include <tf/transform_broadcaster.h>
00046 using namespace std;
00047
00048 #include <iostream>
00049 #include <fstream>
00050
00051 nav_msgs::Odometry odometry_;
00052 sensor_msgs::Imu inercial_;
00053 ros::Time t_i;
00054 ros::Time t_i_1;
00055 ros::Publisher odom_pub;
00056 ros::Publisher imu_pub;
00057
00058 tf::TransformBroadcaster *p_odom_broadcaster;
00062 void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg )
00063 {
00064
00065
00066 inercial_.header.stamp=msg->header.stamp;
00067
00068
00069 tf::StampedTransform transform;
00070
00071
00072 transform.stamp_=msg->header.stamp;
00073 transform.frame_id_="base_footprint";
00074 transform.child_frame_id_ = "/imu_frame";
00075 tf::Vector3 transl(0,0,0);
00076 transl[0]=0;
00077 transl[1]=0;
00078 transl[2]=0;
00079 transform.setOrigin(transl);
00080
00081 tf::Quaternion odom_quat_ = tf::createQuaternionFromRPY(0,0,0);
00082 transform.setRotation(odom_quat_);
00083
00084 p_odom_broadcaster->sendTransform(transform);
00085
00086
00087 inercial_.header.frame_id = "/imu_frame";
00088
00089 tf::Quaternion orientation;
00090 tf::quaternionMsgToTF(msg->orientation, orientation);
00091 double roll,pitch,yaw;
00092 tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
00093
00094 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromRollPitchYaw(roll,pitch,yaw);
00095
00096 inercial_.orientation=odom_quat;
00097 inercial_.orientation_covariance[0]= 0.000001;
00098 inercial_.orientation_covariance[4]= 0.000001;
00099 inercial_.orientation_covariance[8]= 0.000001;
00100 inercial_.angular_velocity_covariance[0]= 0.000304617;
00101 inercial_.angular_velocity_covariance[4]= 0.000304617;
00102 inercial_.angular_velocity_covariance[8]= 0.000304617;
00103 inercial_.linear_acceleration_covariance[0]= 0.0000004;
00104 inercial_.linear_acceleration_covariance[4]= 0.0000004;
00105 inercial_.linear_acceleration_covariance[8]= 0.0000004;
00106 imu_pub.publish(inercial_);
00107
00108 }
00109
00110 void OdometryCallback (const nav_msgs::Odometry::ConstPtr &msg )
00111 {
00112
00113 odometry_=*msg;
00114 odometry_.header.stamp=msg->header.stamp;
00115 odometry_.header.frame_id="/world";
00116 odometry_.child_frame_id="base_footprint";
00117
00118 odometry_.pose.covariance[0]=msg->pose.covariance[0];
00119 odometry_.pose.covariance[7]=msg->pose.covariance[7];
00120 odometry_.pose.covariance[14]=99999999999;
00121 odometry_.pose.covariance[21]=99999999999;
00122 odometry_.pose.covariance[28]=99999999999;
00123 odometry_.pose.covariance[35]=msg->pose.covariance[35];
00124
00125
00126 odometry_.twist.covariance[0]=999999;
00127 odometry_.twist.covariance[7]=999999;
00128 odometry_.twist.covariance[14]=999999;
00129 odometry_.twist.covariance[21]=999999;
00130 odometry_.twist.covariance[28]=999999;
00131 odometry_.twist.covariance[35]=999999;
00132
00133 odom_pub.publish(odometry_);
00134
00135
00136 }
00137
00138
00139
00140
00141 int main(int argc, char** argv)
00142 {
00143
00144
00145 ros::init(argc, argv, "imu_egomotion");
00146 ROS_INFO("Starting message edition node");
00147 ros::NodeHandle n;
00148
00149 tf::TransformBroadcaster odom_broadcaster;
00150 p_odom_broadcaster=&odom_broadcaster;
00151
00152 odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
00153 imu_pub = n.advertise<sensor_msgs::Imu>("/imu_data", 50);
00154
00155 ros::Subscriber imu= n.subscribe("/atc/imu/data",1, ImuCallback);
00156 ros::Subscriber odom= n.subscribe("/vhc/odometry",1, OdometryCallback);
00157
00158
00159 ros::Rate loop_rate(1000);
00160 ros::spin();
00161
00162 return 0;
00163 }