PPSClient.cpp 8.51 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
//    ROS node that manages the student's setup.
//    Copyright (C) 2017  Cyrill Burgener, Marco Mueller, Philipp Friedli
//
//    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 "ros/ros.h"
muelmarc's avatar
muelmarc committed
18
#include <stdlib.h>
19
#include <std_msgs/String.h>
20
#include <rosbag/bag.h>
muelmarc's avatar
muelmarc committed
21
#include <ros/package.h>
22

23
#include "d_fall_pps/Controller.h"
24
#include "d_fall_pps/CMQuery.h"
25
26

#include "d_fall_pps/ViconData.h"
27
#include "d_fall_pps/CrazyflieData.h"
28
#include "d_fall_pps/ControlCommand.h"
muelmarc's avatar
muelmarc committed
29
#include "d_fall_pps/CrazyflieContext.h"
30
#include "std_msgs/Int32.h"
31

muelmarc's avatar
muelmarc committed
32

33
#include "d_fall_pps/ControlCommand.h"
34

35
36
#define CMD_USE_SAFE_CONTROLLER 1
#define CMD_USE_CUSTOM_CONTROLLER 2
37
38
#define CMD_USE_CRAZYFLY_ENABLE 3
#define CMD_USE_CRAZYFLY_DISABLE 4
39

40
using namespace d_fall_pps;
41

42
43
//studentID, gives namespace and identifier in CentralManagerService
int studentID;
44

45
//the safe controller specified in the ClientConfig.yaml, is considered trusted
46
ros::ServiceClient safeController;
47
48
//the custom controller specified in the ClientConfig.yaml, is considered untrusted
ros::ServiceClient customController;
49

50
ros::ServiceClient centralManager;
51
ros::Publisher controlCommandPublisher;
52

53
54
rosbag::Bag bag;

55
56
//describes the area of the crazyflie and other parameters
CrazyflieContext context;
57
58
59
60
61
62
63
64

//gather information about other crazyflies --------------------------------------------------------------------------------
/*bool getOtherCrazyflies;
bool getAllCrazyflies;
std::vector<Setpoint> otherSetpoints;
*/
//------------------------------------------------------------------------------------

65
66
//wheter to use safe of custom controller
bool usingSafeController;
67
68
//wheter crazyflie is enabled (ready to fly) or disabled (motors off)
bool crazyflieEnabled;
69

70
71
int safetyDelay;

72
//checks if crazyflie is within allowed area and if custom controller returns no data
73
bool safetyCheck(CrazyflieData data, ControlCommand controlCommand) {
74
75
	
	//position check
76
	if((data.x < context.localArea.xmin) or (data.x > context.localArea.xmax)) {
77
78
		safetyDelay--;
		return false;
muelmarc's avatar
muelmarc committed
79
	}
80
	if((data.y < context.localArea.ymin) or (data.y > context.localArea.ymax)) {
81
82
		safetyDelay--;
		return false;
muelmarc's avatar
muelmarc committed
83
	}
84
	if((data.z < context.localArea.zmin) or (data.z > context.localArea.zmax)) {
85
86
		safetyDelay--;
		return false;
muelmarc's avatar
muelmarc committed
87
	}
88

89
90
	
	return true;
91
}
phfriedl's avatar
phfriedl committed
92

bucyril's avatar
bucyril committed
93
94
95
96
97
98
99
100
101
102
103
void coordinatesToLocal(CrazyflieData& cf) {
	AreaBounds area = context.localArea;
	float originX = (area.xmin + area.xmax) / 2.0;
	float originY = (area.ymin + area.ymax) / 2.0;
	float originZ = (area.zmin + area.zmax) / 2.0;

	cf.x -= originX;
	cf.y -= originY;
	cf.z -= originZ;
}

104
//is called when new data from Vicon arrives
bucyril's avatar
bucyril committed
105
void viconCallback(const ViconData& viconData) {
106
	for(std::vector<CrazyflieData>::const_iterator it = viconData.crazyflies.begin(); it != viconData.crazyflies.end(); ++it) {
bucyril's avatar
bucyril committed
107
		CrazyflieData global = *it;
108
		
bucyril's avatar
bucyril committed
109
		if(global.crazyflieName == context.crazyflieName) {
110
			Controller controllerCall;
111
			
bucyril's avatar
bucyril committed
112
113
114
			CrazyflieData local = global;
			coordinatesToLocal(local);
			controllerCall.request.ownCrazyflie = local;
115
116
117
118
			
			if(crazyflieEnabled){
				if(!usingSafeController) {
					bool success = customController.call(controllerCall);
119
					
120
121
					if(!success) {
						ROS_ERROR("Failed to call custom controller, switching to safe controller");
bucyril's avatar
bucyril committed
122
						ROS_ERROR_STREAM("custom controller status: valid: " << customController.isValid() << ", exists: " << customController.exists());
phfriedl's avatar
phfriedl committed
123
						ROS_ERROR_STREAM("custom controller name: " << customController.getService());
124
						usingSafeController = true;
muelmarc's avatar
muelmarc committed
125
126
					} else if(!safetyCheck(global, controllerCall.response.controlOutput)) {
						usingSafeController = true;
127
						ROS_INFO_STREAM("safety check failed, switching to safe controller");
128
					}
129
				}
130

131
				
132
133
134
				if(usingSafeController) {
					bool success = safeController.call(controllerCall);
					if(!success) {
bucyril's avatar
bucyril committed
135
						ROS_ERROR_STREAM("Failed to call safe controller, valid: " << safeController.isValid() << ", exists: " << safeController.exists());
136
					}
137
				}
138
139
				
				//ROS_INFO_STREAM("safe controller active: " << usingSafeController);
140

141
142
				controlCommandPublisher.publish(controllerCall.response.controlOutput);

bucyril's avatar
bucyril committed
143
				bag.write("ViconData", ros::Time::now(), local);
144
				bag.write("ControlOutput", ros::Time::now(), controllerCall.response.controlOutput);
muelmarc's avatar
muelmarc committed
145
			
146
147
148
149
			} else { //crazyflie disabled
				ControlCommand zeroOutput = ControlCommand(); //everything set to zero
				zeroOutput.onboardControllerType = 2; //set to motor_mode
				controlCommandPublisher.publish(zeroOutput);
bucyril's avatar
bucyril committed
150
				bag.write("ViconData", ros::Time::now(), local);
151
152
				bag.write("ControlOutput", ros::Time::now(), zeroOutput);
			}
153
		}
154
155
156
157
	}
}

void loadParameters(ros::NodeHandle& nodeHandle) {
158
159
	if(!nodeHandle.getParam("studentID", studentID)) {
		ROS_ERROR("Failed to get studentID");
160
		studentID = 5;
161
	}
162
163
}

164
void loadCrazyflieContext() {
165
166
	CMQuery contextCall;
	contextCall.request.studentID = studentID;
167
168
169
	studentID = 5;
	ROS_INFO_STREAM("myID:" << studentID);
	
170
171
172
173
	centralManager.waitForExistence(ros::Duration(-1));

	if(centralManager.call(contextCall)) {
		context = contextCall.response.crazyflieContext;
174
		ROS_INFO_STREAM("CrazyflieContext:\n" << context);
175
	} else {
176
		ROS_ERROR("Failed to load context");
177
	}
178
179
180

	ros::NodeHandle nh("CrazyRadio");
	nh.setParam("crazyFlieAddress", context.crazyflieAddress);
181
}
182

183
184
185
186
187
188
189
190
191
192
void loadSafeController() {
	ros::NodeHandle nodeHandle("~");

	std::string safeControllerName;
	if(!nodeHandle.getParam("safeController", safeControllerName)) {
		ROS_ERROR("Failed to get safe controller name");
		return;
	}

	ros::service::waitForService(safeControllerName);
193
194
	safeController = ros::service::createClient<Controller>(safeControllerName, true);
    ROS_INFO_STREAM("loaded safe controller: " << safeController.getService());
195
196
197
}

void loadCustomController() {
198
199
	ros::NodeHandle nodeHandle("~");

200
201
202
203
	std::string customControllerName;
	if(!nodeHandle.getParam("customController", customControllerName)) {
		ROS_ERROR("Failed to get custom controller name");
		return;
204
205
	}

bucyril's avatar
bucyril committed
206
	customController = ros::service::createClient<Controller>(customControllerName, true);
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
    ROS_INFO_STREAM("loaded custom controller " << customControllerName);
}

void commandCallback(const std_msgs::Int32& commandMsg) {
	int cmd = commandMsg.data;
	switch(cmd) {
    	case CMD_USE_SAFE_CONTROLLER:
    		loadSafeController();
    		usingSafeController = true;
    		break;

    	case CMD_USE_CUSTOM_CONTROLLER:
    		loadCustomController();
    		usingSafeController = false;
    		break;

223
224
225
226
227
228
229
230
    	case CMD_USE_CRAZYFLY_ENABLE:
    		crazyflieEnabled = true;
    		break;

    	case CMD_USE_CRAZYFLY_DISABLE:
    		crazyflieEnabled = false;
    		break;

231
232
233
    	default:
    		ROS_ERROR_STREAM("unexpected command number: " << cmd);
    		break;
234
	}
235
236
237
238
239
240
}

int main(int argc, char* argv[]){
	ros::init(argc, argv, "PPSClient");
	ros::NodeHandle nodeHandle("~");
	loadParameters(nodeHandle);
241
	
242
243
	
	//ros::service::waitForService("/CentralManagerService/CentralManager");
244
	centralManager = nodeHandle.serviceClient<CMQuery>("/CentralManagerService/Query", false);
245
246
	loadCrazyflieContext();
	
247
248
	//keeps 100 messages because otherwise ViconDataPublisher would override the data immediately
	ros::Subscriber viconSubscriber = nodeHandle.subscribe("/ViconDataPublisher/ViconData", 100, viconCallback);
249
	ROS_INFO_STREAM("successfully subscribed to ViconData");
muelmarc's avatar
muelmarc committed
250
	
251
	//ros::Publishers to advertise the control output
bucyril's avatar
bucyril committed
252
	controlCommandPublisher = nodeHandle.advertise <ControlCommand>("ControlCommand", 1);
phfriedl's avatar
phfriedl committed
253

254
255
	//this topic lets the PPSClient listen to the terminal commands
    ros::Publisher commandPublisher = nodeHandle.advertise<std_msgs::Int32>("Command", 1);
bucyril's avatar
bucyril committed
256
    ros::Subscriber commandSubscriber = nodeHandle.subscribe("Command", 1, commandCallback);
phfriedl's avatar
phfriedl committed
257

258
	//start with safe controller
259
	crazyflieEnabled = true;
260
261
	usingSafeController = true;
	loadSafeController();
262
	
muelmarc's avatar
muelmarc committed
263
264
265
	std::string package_path;
	package_path = ros::package::getPath("d_fall_pps") + "/";
	ROS_INFO_STREAM(package_path);
266
	std::string record_file = package_path + "LoggingPPSClient.bag";
muelmarc's avatar
muelmarc committed
267
268
	bag.open(record_file, rosbag::bagmode::Write);

269
    ros::spin();
muelmarc's avatar
muelmarc committed
270
	bag.close();
271
    return 0;
272
}