UWBDataPublisher.cpp 4.09 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
//    ROS node that publishes the localization data from sensor fusion of the crazyflie, using uwb for coordinates
//    Copyright (C) 2017  Michael Rogenmoser, Tiago Salzmann, Yvan Bosshard
//
//    This program is free software: you can redistribute it and/or modify
//    it under the terms of the GNU General Public License as published by
//    the Free Software Foundation, either version 3 of the License, or
//    (at your option) any later version.
//
//    This program is distributed in the hope that it will be useful,
//    but WITHOUT ANY WARRANTY; without even the implied warranty of
//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
//    GNU General Public License for more details.
//
//    You should have received a copy of the GNU General Public License
//    along with this program.  If not, see <http://www.gnu.org/licenses/>.

#include <string.h>
#include "DataStreamClient.h"
#include "ros/ros.h"
#include "d_fall_pps/CrazyflieContext.h"
#include "std_msgs/Float32.h"
#include "std_msgs/Float32MultiArray.h"
#include "d_fall_pps/CrazyflieData.h"

#include "d_fall_pps/CMQuery.h"

#include "UWBDataPublisher"

using namespace d_fall_pps;

// the clientID defines namespace and identifier in the CentralManagerService
int clientID;

CrazyflieContext context;
rosbag::Bag bag;

ros::Publisher UWBDataPublisher;

double[3] rollPitchYaw;

int main(int argc, char* argv[])
{
    ros::init(argc, argv, "UWBDataPublisher");

    ros::NodeHandle nodeHandle("~");
    ros::Time::init();

    if(!loadParameters(nodeHandle))
    return -1;

    loadCrazyflieContext();    

    UWBDataPublisher = nodeHandle.advertise<CrazyflieData>("UWBData", 1);
 
    ros::NodeHandle namespaceNodeHandle = ros::NodeHandle();
    ros::Subscriber cfRPYSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/RPY",10,cfRPYCallback);

    ros::Subscriber cfXYZSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/XYZ",10,cfXYZCallback);

    ros::Subscriber cfDistancesSubscriber = namespaceNodeHandle.subscribe("CrazyRadio/distances",10,cfDistancesCallback);

    bag.open(record_file, rosbag::bagmode::Write);

    ros::spin();

    bag.close();
    
    return 0;
}

//Callback function to handle roll pitch yaw information from CF
void d_fall_pps::cfRPYCallback(const std_msgs::Float32MultiArray &arrRPY)
{
	rollPitchYaw = (double)arrRPY.data;
}

//Callback funtion to hande x y z information from CF
void cfXYZCallback(const std_msgs::Float32MultiArray &arrXYZ)
{
	CrazyflieData data;

	data.crazyflieName = context.crazyflieName;
	data.x = (double)arrXYZ.data[0];
	data.y = (double)arrXYZ.data[1];
	data.z = (double)arrXYZ.data[2];
	data.roll = rollPitchYaw[0];
	data.pitch = rollPitchYaw[1];
	data.yaw = rollPitchYaw[2];
	data.occluded = false;
	data.acquiringTime = 0; //???

	UWBDataPublisher.publish(data);
	
}

//Callback function to handle distance information from CF
void cfDistancesCallback(const std_msgs::Float32MultiArray &distances)
{
    CrazyflieData data;
    
    double[3] arrXYZ = [0,0,0];

	calculateXYZ((double)distances.data, arrXYZ);   //TODO: Implement!!!
	
	data.crazyflieName = context.crazyflieName;
	data.x = arrXYZ[0];
	data.y = arrXYZ[1];
	data.z = arrXYZ[2];
	data.roll = rollPitchYaw[0];
	data.pitch = rollPitchYaw[1];
	data.yaw = rollPitchYaw[2];
	data.occluded = false;
	data.acquiringTime = 0; //???
	
	UWBDataPublisher.publish(data);
	
}

//calculates position from anchor locations and distances -> forces algorithm?
void calculateXYZ(const double[] &distances, double(&xyz)[3])
{
    //add algorithm from forces - paul

    return;
}

// Loads the current context of the client
void d_fall_pps::loadCrazyflieContext()
{
	CMQuery contextCall;
	contextCall.request.studentID = clientID;

	centralManager.waitForExistence(ros::Duration(-1));

	if(centralManager.call(contextCall))
	{
		context =contextCall.response.crazyflieContext;

		ROS_INFO_STREAM("LocalizationServer context updated");
	}
}

// Loads the parameters of the node handle
bool d_fall_pps::loadParameters(ros::NodeHandle &nodeHandle)
{
	if(!nodeHandle.getParam("clientID", clientID))
	{
		ROS_ERROR("Failed to get clientID!");
		return false;
	}

	return true;
}