1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
|
/*
* =====================================================================================
*
* Filename: main.cpp
*
* Description: Main code for reflections SLAM. While the code is primarily
* designed to run in ROS, an attempt is being made to allow some
* functionality without it. However, no guarantees are made that the two
* will produce the same outputs for a given input.
*
* Version: 1.0
* Created: 03/17/2017 04:12:33 PM
* Revision: none
* Compiler: gcc
*
* Author: Martin Miller (MHM), miller7@illinois.edu
* Organization: Aerospace Robotics and Controls Lab (ARC)
*
* =====================================================================================
*/
#include "main.h"
bool seenutm=false;
bool seenpva=false;
#ifdef USE_ROS
#else /* ----- not USE_ROS ----- */
void
imgCallback(const message *msg)
{
return;
}
void
imuCallback(const message &msg, Eigen::Matrix<double,9,1> &X, const Eigen::Quaternion<double> &q, const timestamp dt)
{
if (!seenutm || !seenpva || (dt.secs==0 && dt.nsecs==0)) return;
using Eigen::Vector3d;
Vector3d acc(msg.linear_acceleration.y,msg.linear_acceleration.x,-msg.linear_acceleration.z);
Vector3d ang(msg.angular_velocity.y,msg.angular_velocity.x,-msg.angular_velocity.z);
// WARNING: This is the bias for 1112-1
Vector3d ang_bias(-2.795871394666666222e-03, 6.984255690000021506e-03, 1.418145565750002614e-03);
ang-=ang_bias;
Body mu;
double dtf = dt.secs+dt.nsecs*1e-9;
mu.motionModel(X,acc,ang,q,dtf);
}
void
pvaCallback(const message &msg, Eigen::Matrix<double,9,1> &X, Eigen::Quaternion<double> &q)
{
using Eigen::AngleAxisd;
using Eigen::Vector3d;
double roll, pitch, yaw;
attitude_t A=msg.attitude;
roll = M_PI*msg.attitude.roll/180.;
pitch = M_PI*msg.attitude.pitch/180.;
yaw = M_PI*(msg.attitude.yaw)/180.;
Eigen::Matrix3d R;
R = AngleAxisd(yaw, Vector3d::UnitZ())
* AngleAxisd(roll, Vector3d::UnitX())
* AngleAxisd(pitch, Vector3d::UnitY());
q = Eigen::Quaternion<double>(R);
if (!seenpva) {
Vector3d vw(msg.velocity.north,msg.velocity.east,-msg.velocity.up);
X.segment(3,3) = R.transpose()*vw;
seenpva=true;
}
return;
}
void
utmCallback(const message &msg, Eigen::Matrix<double,9,1> &X)
{
if (!seenutm) {
seenutm=true;
X[0] = msg.utm.northing;
X[1] = msg.utm.easting;
X[2] = -msg.utm.up;
}
return;
}
#endif /* ----- not USE_ROS ----- */
int
parseLine(char *line, message *data)
{
char *time_string;
char *msg_type;
double t;
int s,ns;
time_string = strsep(&line, ",");
msg_type = strsep(&line, ",");
sscanf(time_string,"%lf", &t);
s = (int) t;
ns = (int) ((t-s)*1e9);
data->stamp.secs=s;
data->stamp.nsecs=ns;
if (!strcmp(msg_type,"bestutm")) {
data->msg_type = BESTUTM;
sscanf(line,"%d,%c,%lf,%lf,%lf",
&data->utm.zone_i,
&data->utm.zone_c,
&data->utm.northing,
&data->utm.easting,
&data->utm.up);
} else if (!strcmp(msg_type,"IMG")) {
data->msg_type = IMG;
char *lfn,*rfn;
lfn = strsep(&line, ",");
sscanf(lfn, "%s", &data->image_names);
rfn = strsep(&line, ",");
sscanf(rfn, "%s", &data->image_names+1);
} else if (!strcmp(msg_type,"inscovs")) {
data->msg_type = INSCOVS;
} else if (!strcmp(msg_type,"inspvas")) {
data->msg_type = INSPVAS;
sscanf(line,"%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf,%lf",
&data->position.latitude,
&data->position.longitude,
&data->position.altitude,
&data->velocity.north,
&data->velocity.east,
&data->velocity.up,
&data->attitude.roll,
&data->attitude.pitch,
&data->attitude.yaw);
} else if (!strcmp(msg_type,"rawimus")) {
data->msg_type = RAWIMUS;
double acc_y, ang_y;
sscanf(line,"%lf,%lf,%lf,%lf,%lf,%lf",
&data->linear_acceleration.z,
&acc_y,
&data->linear_acceleration.x,
&data->angular_velocity.z,
&ang_y,
&data->angular_velocity.x);
data->linear_acceleration.y = -acc_y;
data->angular_velocity.y = -ang_y;
} else {
fprintf(stderr, "Message type %s is unknown, quitting.\n", msg_type);
exit(1);
}
}
timestamp
update_dt(const timestamp t, timestamp *t_old)
{
double dtf=0;
if (t_old->secs!=0 || t_old->nsecs!=0) {
double tf = t.secs+1e-9*t.nsecs;
double t_oldf = t_old->secs+1e-9*t_old->nsecs;
dtf = tf-t_oldf;
}
t_old->secs=t.secs;
t_old->nsecs=t.nsecs;
timestamp dt;
dt.secs = (int) dtf;
dt.nsecs = (int)((dtf-(double)dt.secs)*1e9);
return dt;
}
int
main(int argc, char **argv)
{
Eigen::Quaternion<double> qbw;
Eigen::Matrix<double,9,1> bodyStateVector;
// bias in FRD coordinates
bodyStateVector.segment(6,3) << 0.975*-0.03713532, 0.9*0.01465135, -0.00709229;
timestamp dt{0,0};
timestamp t_old{0,0};
#ifdef USE_ROS
#else /* ----- not USE_ROS ----- */
using std::cout;
using std::endl;
using std::cerr;
printf("UTM-Zone,UTM-Ch,UTM-North,UTM-East\n");
// Read sensors from file
char line[MAXLINE];
while (scanf("%s", line)!=EOF) {
message msg;
parseLine(line, &msg);
switch ( msg.msg_type ) {
case BESTUTM:
dt = update_dt(msg.stamp, &t_old);
utmCallback(msg,bodyStateVector);
break;
case IMG:
imgCallback(&msg);
break;
case INSPVAS:
dt = update_dt(msg.stamp, &t_old);
pvaCallback(msg, bodyStateVector, qbw);
//std::cout << bodyStateVector.transpose() << std::endl;
if (seenutm)
printf("%d,%c,%f,%f\n", msg.utm.zone_i,msg.utm.zone_c,bodyStateVector[0],bodyStateVector[1]);
break;
case RAWIMUS:
dt = update_dt(msg.stamp, &t_old);
imuCallback(msg, bodyStateVector, qbw, dt);
break;
default:
break;
} /* ----- end switch ----- */
}
#endif /* ----- not USE_ROS ----- */
return 0;
}
|