Commit d25ade15 authored by muelmarc's avatar muelmarc
Browse files

updates from yesterday for data recording

parent f4f59b73
......@@ -72,6 +72,8 @@ add_message_files(
CrazyflieContext.msg
AreaBounds.msg
Setpoint.msg
CrazyflieEntry.msg
CrazyflieDB.msg
)
## Generate services in the 'srv' folder
......@@ -83,7 +85,10 @@ add_message_files(
add_service_files(
FILES
Controller.srv
CentralManager.srv
CMRead.srv
CMQuery.srv
CMUpdate.srv
CMCommand.srv
)
## Generate actions in the 'action' folder
......
string crazyflieName
string crazyflieAddress
AreaBounds localArea
CrazyflieEntry[] crazyflieEntries
CrazyflieContext crazyflieContext
uint32 studentID
......@@ -14,12 +14,26 @@
// 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 <stdlib.h>
#include "ros/ros.h"
#include "d_fall_pps/CrazyflieContext.h"
#include "d_fall_pps/CentralManager.h"
#include "d_fall_pps/CrazyflieContext.h"
#include "d_fall_pps/CrazyflieDB.h"
#include "d_fall_pps/CrazyflieContext.h"
using namespace d_fall_pps;
using namespace std;
//reads crazyflie db from the file specified in params
/*CrazyflieDB readCrazyflieDB() {
return 0;
}*/
//writes crazyflie db to the file specified in params
void writeCrazyflieDB(CrazyflieDB& cfDB) {
}
/*
//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)
......@@ -40,16 +54,46 @@ bool returnCrazyflieContext(CentralManager::Request &request, CentralManager::Re
return true;
}
bool cmRead(CMRead::Request &request, CMRead::Response &response) {
ROS_INFO("central manager");
//TBD: crazyflie-dependent area assignment instead of hardcoding
//request contains string crazyflieName
//respond with area boundaries upon request
response.context.localArea.xmin = -1.5;
response.context.localArea.xmax = 1.5;
response.context.localArea.ymin = -1.5;
response.context.localArea.ymax = 1.5;
response.context.localArea.zmin = -0.25;
response.context.localArea.zmax = 0.8;
return true;
}
bool cmQuery(CMQuery::Request &request, CMQuery::Response &response) {
ROS_INFO("central manager");
//TBD: crazyflie-dependent area assignment instead of hardcoding
//request contains string crazyflieName
//respond with area boundaries upon request
response.context.localArea.xmin = -1.5;
response.context.localArea.xmax = 1.5;
response.context.localArea.ymin = -1.5;
response.context.localArea.ymax = 1.5;
response.context.localArea.zmin = -0.25;
response.context.localArea.zmax = 0.8;
return true;
}*/
int main(int argc, char* argv[]) {
ros::init(argc, argv, "CentralManagerService");
ros::NodeHandle nodeHandle("~");
ros::ServiceServer service = nodeHandle.advertiseService("CentralManager", returnCrazyflieContext);
//ros::ServiceServer service = nodeHandle.advertiseService("CMRead", cmRead);
ROS_INFO("CentralManagerService ready");
ros::spin();
......
uint32 command #save, reload
---
---
CrazyflieDB crazyflieDB
CrazyflieEntry crazyflieEntry
uint32 mode #insert/update, remove
---
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment