imu_data_confidence.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 ***************************************************************************************************/
31 #include <sensor_msgs/Imu.h>
32 // #include "tf/transform_datatypes.h"
33 #include <tf/transform_listener.h>
34 #include <nav_msgs/Odometry.h>
35 #include <stdio.h>
36 // #include <atlascar_base/AtlascarStatus.h>
37 #include <std_msgs/Float64.h>
38 // #include <atlascar_base/AtlascarVelocityStatus.h>
39 using namespace std;
40 using namespace ros;
41 
42 
43 //
44 std_msgs::Float64 acc_norm_imu,tan_msg,cent_msg;
45 //
46 ros::Publisher* p_pitch_pub;
47 nav_msgs::Odometry odometry_;
48 sensor_msgs::Imu imu_data;
49 // atlascar_base::AtlascarStatus base_status;
50 // atlascar_base::AtlascarVelocityStatus base_velocity;
51 ros::Time t_i, t_i_1;
52 double vl_i,vl_i_1;
53 bool bool_init=true;
54 double v_ant;
55 void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg )
56 {
57  imu_data=*msg;
58 }
59 
60 // void VelocityMessageHandler(const atlascar_base::AtlascarVelocityStatus& msg)
61 // {
62 // base_velocity=msg;
63 // if(bool_init)
64 // {
65 // t_i_1=msg.header.stamp;
66 // t_i=msg.header.stamp;
67 // bool_init=false;
68 // }else
69 // {
70 // t_i_1=t_i;
71 // t_i=msg.header.stamp;
72 // }
73 // }
74 // void StatusMessageHandler(const atlascar_base::AtlascarStatus& msg)
75 // {
76 // base_status=msg;
77 // }
78 //this node just completes the information necessary to robot_pose_ekf
79 int main(int argc, char** argv)
80 {
81 
82  ros::init(argc, argv, "imu_egomotion");
83  ros::NodeHandle n;
84 
85  Subscriber imu= n.subscribe("/atc/imu/data",1, ImuCallback);
86 // Subscriber subscribeStatusMessages = n.subscribe ("/vhc/plc/status", 1, StatusMessageHandler);
87 // Subscriber subscribeVelocityStatusMessages = n.subscribe ("/vhc/velocity/status", 1, VelocityMessageHandler);
88 
89  Publisher imu_norm=n.advertise<std_msgs::Float64>("/imu_norm",50);
90  Publisher accel_tan=n.advertise<std_msgs::Float64>("/accel_tan",50);
91  Publisher accel_cent=n.advertise<std_msgs::Float64>("/accel_cent",50);
92 
93  ros::Rate r(20.0);
94 
95  ROS_INFO("Starting to spin ...");
96  double vl,phi;
97  double phi_tmp=0;
98 
99  while(n.ok())
100  {
101  ROS_ERROR("Message type changed, AtlascarStatus and AtlascarVelocityStatus no longer avaliable!! please correct");
102 
103  spinOnce();
104  r.sleep();
105 
106 
107 // vl=base_velocity.velocity;
108 // phi=base_status.steering_wheel;
109 
110  if (phi ==0)
111  phi=phi_tmp;
112  else
113  phi_tmp=phi;
114 
115 
116  //CALIBRATING STEERING WHEEL
117  //phi correction
118  phi= phi +0.275;
119 
120  if (phi <=0)
121  {
122  phi = phi*0.74;
123  phi=phi*-1;
124  }
125  else if (phi>0)
126  {
127  phi= phi*0.825;
128  phi=phi*-1;
129  }
130 
131  //corrrection velocity car like robot
132  double w=1.27;
133  double l=2.6;
134  double instant_radious=fabs(l/tan(phi));
135  double v_corrected;
136  if(phi>=0)
137  v_corrected=vl*(instant_radious/(instant_radious-w/2));
138  else
139  v_corrected=vl*(instant_radious/(instant_radious+w/2));
140 
141  cout << "vl_ant" << v_ant << "\n"<< endl;
142  cout << "vl" << vl << "\n"<< endl;
143  cout << "vl_corre" << v_corrected << "\n"<< endl;
144  //inst. radious
145  //aceleração centripeta
146  double dt = (t_i - t_i_1).toSec();
147  double acc_cent=(v_corrected*v_corrected)/instant_radious;
148  //cout << "acc_cent" << acc_cent << "\n"<< endl;
149 // double acc_tan=(v_corrected-v_ant)/dt;
150  //cout << "acc_tan" << acc_tan << "\n"<< endl;
151  v_ant=v_corrected;
152  //tan_msg.data=acc_tan;
153  tan_msg.data=dt;
154  accel_tan.publish(tan_msg);
155 
156  cent_msg.data=acc_cent;
157  accel_cent.publish(cent_msg);
158  //imu data
159  double accel_norm= sqrt((imu_data.linear_acceleration.x * imu_data.linear_acceleration.x) + (imu_data.linear_acceleration.y * imu_data.linear_acceleration.y) + (imu_data.linear_acceleration.z * imu_data.linear_acceleration.z));
160 
161  //cout << "accel_norm" << accel_norm-9.81 << endl;
162  acc_norm_imu.data=accel_norm;
163  imu_norm.publish(acc_norm_imu);
164 
165 
166  }
167  return 0;
168 }
int main(int argc, char **argv)
double vl_i_1
bool bool_init
nav_msgs::Odometry odometry_
void ImuCallback(const sensor_msgs::Imu::ConstPtr &msg)
ros::Time t_i_1
ros::Time t_i
sensor_msgs::Imu imu_data
ros::Publisher * p_pitch_pub
std_msgs::Float64 acc_norm_imu
std_msgs::Float64 cent_msg
std_msgs::Float64 tan_msg
double vl_i
double v_ant


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