Skip to content
Snippets Groups Projects
Commit 88d236aa authored by roangel's avatar roangel
Browse files

Merge branch 'pps_project' of https://gitlab.ethz.ch/D-FaLL/D-FaLL-System into pps_project

parents 5d9ffdd3 d5f67a1d
No related branches found
No related tags found
No related merge requests found
Showing
with 81 additions and 20 deletions
File deleted
File deleted
File deleted
File deleted
File deleted
File deleted
File deleted
File deleted
File deleted
File deleted
File deleted
File deleted
TeamName: 'Two'
CrazyFlieName: "cfTwo"
CrazyFlieAddress: "radio://0/99/2M"
SafeController: ""
SafeControllerType: ""
CustomController: ""
CustomControllerType: ""
#controllertypes to add with adjustable
#motor, angle and rate
float32 xmin
float32 xmax
float32 ymin
float32 ymax
float32 zmin
float32 zmax
AreaBounds localArea
// The service that manages the context of the student groups.
// 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"
#include "d_fall_pps/CrazyflieContext.h"
#include "d_fall_pps/CentralManager.h"
using namespace d_fall_pps;
//receive request from students (containing (maybe among other things) their name)
//send them back the CrazyflieContext (containing (maybe among other things) the area to fly in)
bool returnCrazyflieContext(CentralManager::Request &request, CentralManager::Response &response) {
ROS_INFO("central manager");
return true;
}
int main(int argc, char* argv[]) {
ros::init(argc, argv, "CentralManagerService");
ros::NodeHandle nodeHandle("~");
ros::ServiceServer service = nodeHandle.advertiseService("CentralManager", returnCrazyflieContext);
ROS_INFO("CentralManagerService ready");
ros::spin();
return 0;
}
......@@ -29,6 +29,8 @@
#include "d_fall_pps/AngleCommand.h"
#include "d_fall_pps/RateCommand.h"
#include "d_fall_pps/MotorCommand.h"
#include "d_fall_pps/CrazyflieContext.h"
using namespace d_fall_pps;
......@@ -47,23 +49,18 @@ ros::Publisher motorCommandPublisher;
//ros::NodeHandle nodeHandle;
//acceptance test for crazyflie position and attitude
bool safetyCheck(ViconData data){
CrazyflieContext CrazyflieContext;
return true;
}
//extract data from "data" and publish/add to service for controller
//not void: sould give back controlldata
void ppsClientToController(ViconData data){
void ppsClientToController(ViconData data, bool autocontrol){
if(data.crazyflieName == cflie){
/* unnecessairy: just send data!!!!!
d_fall_pps::ViconData myDataToPublish;
myDataToPublish.crazyflieName = data.crazyflieName;
myDataToPublish.x = data.x;
myDataToPublish.y = data.y;
myDataToPublish.z = data.z;
myDataToPublish.roll = data.roll;
myDataToPublish.pitch = data.pitch;
myDataToPublish.yaw = data.yaw;
myDataToPublish.acquiringTime = data.acquiringTime;
*/
//TODO:
//Some way of choosing the correct controller: Safe or Custom
//using the area data
......@@ -106,13 +103,15 @@ void viconCallback(const d_fall_pps::ViconData& data){
//debugging
//++callbackCalls;
//ROS_INFO("Callback called #%d",callbackCalls);
//ROS_INFO("Recived Pitch in this callback: %f", data.pitch);
//ROS_INFO("Received Pitch in this callback: %f", data.pitch);
//ROS_INFO("received data:"); ROS_INFO_STREAM(data);
//ROS_INFO("My teamname is:"); ROS_INFO_STREAM(team);
//ROS_INFO("My crazyflie is:"); ROS_INFO_STREAM(cflie);
//extract data from "data" and publish/add to service for controller
ppsClientToController(data);
//forward data to safety check
bool autocontrolOn = safetyCheck(data);
ppsClientToController(data, autocontrolOn);
}
......@@ -192,9 +191,9 @@ int main(int argc, char* argv[]){
//ros::Publishers to advertise on the three command type topics
angleCommandPublisher = nodeHandle.advertise <d_fall_pps::AngleCommand>("AngleCommand", 1000);
rateCommandPublisher = nodeHandle.advertise<d_fall_pps::RateCommand>("RateCommand", 1000);
motorCommandPublisher = nodeHandle.advertise <d_fall_pps::MotorCommand>("MotorCommand", 1000);
angleCommandPublisher = nodeHandle.advertise <d_fall_pps::AngleCommand>("AngleCommand", 1);
rateCommandPublisher = nodeHandle.advertise<d_fall_pps::RateCommand>("RateCommand", 1);
motorCommandPublisher = nodeHandle.advertise <d_fall_pps::MotorCommand>("MotorCommand", 1);
//service: now only one available: to add several services depending on controller
......
string crazyflieName
---
CrazyflieContext context
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment