add_imu_odometry_covariance.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include <sensor_msgs/Imu.h>
33 #include "geometry_msgs/Vector3Stamped.h"
34 #include "geometry_msgs/QuaternionStamped.h"
35 // #include "tf/transform_datatypes.h"
36 #include "geometry_msgs/Pose.h"
37 #include <sensor_msgs/JointState.h>
38 #include <tf/transform_listener.h>
39 #include <nav_msgs/Odometry.h>
40 #include "geometry_msgs/Pose.h"
41 #include "geometry_msgs/Quaternion.h"
42 #include "tf/transform_datatypes.h"
43 #include <stdio.h>
44 #include <std_msgs/Float64.h>
45 #include <tf/transform_broadcaster.h>
46 using namespace std;
47 
48 #include <iostream>
49 #include <fstream>
50 
51 nav_msgs::Odometry odometry_;
52 sensor_msgs::Imu inercial_;
53 ros::Time t_i;
54 ros::Time t_i_1;
55 ros::Publisher odom_pub;
56 ros::Publisher imu_pub;
57 
58 tf::TransformBroadcaster *p_odom_broadcaster;
62 void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg )
63 {
64  // ROS_INFO("imu message received");
65  // inercial_=*msg;
66  inercial_.header.stamp=msg->header.stamp;//mudar!!
67 
68 
69  tf::StampedTransform transform;
70 
71  //Transformation necessary to the robot_pose_ekf node
72  transform.stamp_=msg->header.stamp;
73  transform.frame_id_="base_footprint";
74  transform.child_frame_id_ = "/imu_frame";
75  tf::Vector3 transl(0,0,0);
76  transl[0]=0;
77  transl[1]=0;
78  transl[2]=0;
79  transform.setOrigin(transl);
80 
81  tf::Quaternion odom_quat_ = tf::createQuaternionFromRPY(0,0,0);
82  transform.setRotation(odom_quat_);
83  //Publicar nova tf
84  p_odom_broadcaster->sendTransform(transform);
85 
86 
87  inercial_.header.frame_id = "/imu_frame";
88 
89  tf::Quaternion orientation;
90  tf::quaternionMsgToTF(msg->orientation, orientation);
91  double roll,pitch,yaw;
92  tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
93  //geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromRollPitchYaw(yaw,-pitch,-roll);
94  geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromRollPitchYaw(roll,pitch,yaw);
95 
96  inercial_.orientation=odom_quat;
97  inercial_.orientation_covariance[0]= 0.000001;
98  inercial_.orientation_covariance[4]= 0.000001;
99  inercial_.orientation_covariance[8]= 0.000001;
100  inercial_.angular_velocity_covariance[0]= 0.000304617;
101  inercial_.angular_velocity_covariance[4]= 0.000304617;
102  inercial_.angular_velocity_covariance[8]= 0.000304617;
103  inercial_.linear_acceleration_covariance[0]= 0.0000004;
104  inercial_.linear_acceleration_covariance[4]= 0.0000004;
105  inercial_.linear_acceleration_covariance[8]= 0.0000004;
106  imu_pub.publish(inercial_);
107 
108 }
109 
110 void OdometryCallback (const nav_msgs::Odometry::ConstPtr &msg )
111 {
112  // ROS_INFO("odometry message received");
113  odometry_=*msg;
114  odometry_.header.stamp=msg->header.stamp;
115  odometry_.header.frame_id="/world";
116  odometry_.child_frame_id="base_footprint";
117 
118  odometry_.pose.covariance[0]=msg->pose.covariance[0];
119  odometry_.pose.covariance[7]=msg->pose.covariance[7];
120  odometry_.pose.covariance[14]=99999999999;
121  odometry_.pose.covariance[21]=99999999999;
122  odometry_.pose.covariance[28]=99999999999;
123  odometry_.pose.covariance[35]=msg->pose.covariance[35];
124 
125 
126  odometry_.twist.covariance[0]=999999;
127  odometry_.twist.covariance[7]=999999;
128  odometry_.twist.covariance[14]=999999;
129  odometry_.twist.covariance[21]=999999;
130  odometry_.twist.covariance[28]=999999;
131  odometry_.twist.covariance[35]=999999;
132 
133  odom_pub.publish(odometry_);
134 
135 
136 }
137 
138 
139 
140 //this node just completes the information necessary to robot_pose_ekf
141 int main(int argc, char** argv)
142 {
143 
144 
145  ros::init(argc, argv, "imu_egomotion");
146  ROS_INFO("Starting message edition node");
147  ros::NodeHandle n;
148 
149  tf::TransformBroadcaster odom_broadcaster;
150  p_odom_broadcaster=&odom_broadcaster;
151 
152  odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
153  imu_pub = n.advertise<sensor_msgs::Imu>("/imu_data", 50);
154 
155  ros::Subscriber imu= n.subscribe("/atc/imu/data",1, ImuCallback);
156  ros::Subscriber odom= n.subscribe("/vhc/odometry",1, OdometryCallback);
157 
158 
159  ros::Rate loop_rate(1000);
160  ros::spin();
161 
162  return 0;
163 }
void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg)
ImuCallback Function to add covariance to IMU data.
ros::Publisher odom_pub
nav_msgs::Odometry odometry_
int main(int argc, char **argv)
ros::Time t_i
ros::Time t_i_1
tf::TransformBroadcaster * p_odom_broadcaster
sensor_msgs::Imu inercial_
void OdometryCallback(const nav_msgs::Odometry::ConstPtr &msg)
ros::Publisher imu_pub


atlascar_egomotion
Author(s): Pedro Salvado
autogenerated on Mon Mar 2 2015 01:31:26