DataListener.cpp 6.11 KB
Newer Older
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
220
221
222
#include "DataListener.h"

#include "IndoorNewton.h"

#include <string>
#include <vector>

#include "ros/ros.h"
#include <ros/package.h>

bool compare_anchor_data(const anchor_data& a, const anchor_data& b)
{
	if ((a.from == b.from && a.to < b.to) || a.from < b.from)
		return true;

	return false;
}

DataListener::DataListener()
{
	for (unsigned int j = 0; j < 8; j++) {
		_distances[j] = 0;
	}

	offset.x = 0;
	offset.y = 0;
	offset.z = 0;

	elapsedTime = 0;
	remove("AnchorPos.yaml");
	remove("data.txt");
}

DataListener::~DataListener()
{
}

bool DataListener::checkAndReadData(std::string value)
{
	switch (value.at(0))
	{
	case '#':
		_CF_Debugger(value);
		return 1;
		break;
	case '$':
		_LOC_Debugger(value);
		return 1;
		break;
	default:
		break;
	}

	return 0;
}

void DataListener::setOffset(double x, double y, double z)
{
	printf("Offset now is (%.2lf, %.2lf, %.2lf)\n", x, y, z);
	offset.x = x;
	offset.y = y;
	offset.z = z;
}

void DataListener::_CF_Debugger(std::string value)
{
	unsigned int distances[8];
	sscanf(value.c_str(), "#%u/%u/%u/%u/%u/%u/%u/%u/", &distances[0], &distances[1], &distances[2], &distances[3], &distances[4], &distances[5], &distances[6], &distances[7]);

	printf("--- DISTANCE: \t%u \t%u \t%u \t%u \t%u \t%u \t%u \t%u\n", distances[0], distances[1], distances[2], distances[3], \
	       distances[4], distances[5], distances[6], distances[7]);

	/*FILE* file = fopen("data.txt", "a");
	elapsedTime +=  distances[7];
	fprintf(file, "%u\n", elapsedTime);
	fclose(file);*/
}

void DataListener::_LOC_Debugger(std::string value)
{
	unsigned int source, dest, distance;
	sscanf(value.c_str(), "$%u/%u/%u", &source, &dest, &distance);
	distance -= 500; //500;

	anchors.push_back(anchor_data(source, dest, distance));

	printf("--- LOC: \t%u \t%u \t%u\n", source, dest, distance);

	//Reset Timer
	locTimer = std::clock();
}

double DataListener::_get_distance_average(unsigned int anchor_from, unsigned int anchor_to, int& flag)
{
	unsigned int sum = 0;
	unsigned int count = 0;
	std::list<anchor_data>::iterator it;
	for (it = anchors.begin(); it != anchors.end(); it++)
	{
		//Not a measurement from and to
		if (it->from != anchor_from || it->to != anchor_to)
			continue;

		if (it->distance < 10000) //Simple filter -> if the distance is less than 10m = 10'000mm
		{
			sum += it->distance;
			count++;
		}
	}

	//FAILED
	if (count == 0 || sum == 0)
		flag = -1;

	//Divide by 100 to get it in dm
	return ((double)sum / (double)count) / 100.0;
}



////////////////////////////////////////////////////////////
/*

I KNOW, THIS NEWTON ALGORITHM IS MADE FOR 6 ANCHORS. NOT THE BEST SOLUTION WHEN USING ONLY 3 TO DETERMINE
THE POSITION OF THE OTHER ANCHORS, BUT HEY, IT WORKS xD

*/

bool DataListener::calulateAnchorPosition()
{
	//List is not empty and there is a 5s delay after the last received distance

	if (anchors.size() == 0 || (std::clock() - locTimer) / ((double)CLOCKS_PER_SEC) < 2)
		return false;

	anchors.sort(compare_anchor_data);
	int flag = 1;

	double d01, d02, d12;
	d01 = _get_distance_average(0, 1, flag);
	d02 = _get_distance_average(0, 2, flag);
	d12 = _get_distance_average(1, 2, flag);

	double x = (d01 * d01 + d02 * d02 - d12 * d12) / (2 * d02);
	double y = d01 * sin(acos((d01 * d01 + d02 * d02 - d12 * d12) / (2 * d02 * d01)));

	double anchor_positions[18] = {0, 0, 0, \
	                               x, -y, 0, \
	                               d02, 0, 0, \
	                               0, 0, 0, \
	                               x, -y, 0, \
	                               d02, 0, 0
	                              };

	anchor_position.push_back(anchor_position_data(0, anchor_positions[0], anchor_positions[1], anchor_positions[2]));
	anchor_position.push_back(anchor_position_data(1, anchor_positions[3], anchor_positions[4], anchor_positions[5]));
	anchor_position.push_back(anchor_position_data(2, anchor_positions[6], anchor_positions[7], anchor_positions[8]));

	//Error with one of the preset values
	if (flag == -1)
		return false;

	//For anchor n we only need d0n, d1n, d2n
	for (unsigned int n = 3; n < 6; n++)
	{
		int flag = 1;
		double anchor_distances[6] = { _get_distance_average(0, n, flag), _get_distance_average(1, n, flag), _get_distance_average(2, n, flag), \
		                               _get_distance_average(0, n, flag), _get_distance_average(1, n, flag), _get_distance_average(2, n, flag)
		                             };

		if (flag != -1) {
			//Calculate position of anchor n using IndoorNewton
			double result[3];
			IndoorNewton(anchor_positions, anchor_distances, result, 200);

			anchor_position.push_back(anchor_position_data(n, result[0], result[1], result[2]));
		}
	}

	//Save anchor positions to yaml file

	ros::NodeHandle nodeHandle("~");

	std::vector<float> anchorArr;

	for (unsigned int i = 0; i < anchor_position.size(); i++) 
	{
		anchorArr = {anchor_position[i].x - offset.x, anchor_position[i].y - offset.y, anchor_position[i].z - offset.z};
		nodeHandle.setParam("anchor" + std::to_string(i), anchorArr);
	}








	// FILE* file = fopen("AnchorPos.yaml", "w");
	// fprintf(file, "anchorLength: 6   # Update this number after adding/removing anchors!!!\n\n");
	// fprintf(file, "# Structure: anchorID [x, y, z] (ID is always from 0 to length-1)\n\n");

	// printf("%s\n---- ANCHOR POSITIONS ----\n", K_NORMAL);
	// printf("---- Without offset\n");
	// for (unsigned int i = 0; i < anchor_position.size(); i++)
	// 	printf("anchor%u: [%.2lf, %.2lf, %.2lf]\n", i, anchor_position[i].x, anchor_position[i].y, anchor_position[i].z);
	// printf("\n");
	// printf("---- With offset: (%.2lf, %.2lf, %.2lf)\n", offset.x, offset.y, offset.z);
	// for (unsigned int i = 0; i < anchor_position.size(); i++)
	// {
	// 	fprintf(file, "anchor%u: [%.2lf, %.2lf, %.2lf]\n", i, anchor_position[i].x - offset.x, anchor_position[i].y - offset.y, anchor_position[i].z - offset.z);
	// 	printf("%sanchor%u: [%.2lf, %.2lf, %.2lf]\n", K_WARNING, i, anchor_position[i].x - offset.x, anchor_position[i].y - offset.y, anchor_position[i].z - offset.z);
	// }

	// printf("%s---- Saved anchor positions to AnchorPos.yaml\n", K_NORMAL);
	// printf("%s--------------------------\n\n", K_NORMAL);

	// fclose(file);
	// anchors.clear();

	return true;
}