From 66786e595fa930ee9f5cb9d5c91ca548c24076e4 Mon Sep 17 00:00:00 2001
From: Paul Beuchat <beuchatp@control.ee.ethz.ch>
Date: Sat, 4 Apr 2020 00:03:30 +0200
Subject: [PATCH] Fixed some small BUUUUUGGGGGGGSSSS so that the student
 controller service now compiles, mainly missing semi-colons from Jeremys
 edits because he is not able to compile on his machine to find these
 BUGGGGGSSS

---
 .../include/classes/GetParamtersAndNamespaces.h        |  2 +-
 .../dfall_pkg/include/nodes/StudentControllerService.h |  1 +
 .../src/classes/GetParamtersAndNamespaces.cpp          | 10 +++++-----
 .../dfall_pkg/src/nodes/StudentControllerService.cpp   |  8 ++++----
 4 files changed, 11 insertions(+), 10 deletions(-)

diff --git a/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
index 2dabd94a..5c9f4339 100644
--- a/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
+++ b/dfall_ws/src/dfall_pkg/include/classes/GetParamtersAndNamespaces.h
@@ -134,4 +134,4 @@ void constructNamespaceForCoordinatorParameterService( int coordID, std::string
 bool checkMessageHeader( int agentID , bool shouldCheckForAgentID , const std::vector<uint> & agentIDs );
 
 // FUNCTION FOR CONVERTING NEWTON TO MOTOR COMMAND
-float newtons2cmd_for_crazyflie( float thrust)
\ No newline at end of file
+float newtons2cmd_for_crazyflie( float thrust);
\ No newline at end of file
diff --git a/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h b/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
index 91d6b3e8..da904427 100644
--- a/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
+++ b/dfall_ws/src/dfall_pkg/include/nodes/StudentControllerService.h
@@ -69,6 +69,7 @@
 // Include the DFALL service types
 #include "dfall_pkg/LoadYamlFromFilename.h"
 #include "dfall_pkg/GetSetpointService.h"
+#include "dfall_pkg/GetDebugValuesService.h"
 
 // Include the shared definitions
 #include "nodes/Constants.h"
diff --git a/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
index 762adfad..ff6f9bc8 100644
--- a/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
+++ b/dfall_ws/src/dfall_pkg/src/classes/GetParamtersAndNamespaces.cpp
@@ -266,15 +266,15 @@ float newtons2cmd_for_crazyflie( float thrust)
 	// Compute the 16-bit command that would produce the requested
 	// "thrust" based on the quadratic mapping that is described
 	// by the coefficients in the "yaml_motorPoly" variable.
-	float motoPoly = [5.484560e-4, 1.032633e-6, 2.130295e-11]
+	static float motorPoly[3] = {5.484560e-4, 1.032633e-6, 2.130295e-11};
 
 	float cmd_16bit = (-motorPoly[1] + sqrt(motorPoly[1] * motorPoly[1] - 4 * motorPoly[2] * (motorPoly[0] - thrust))) / (2 * motorPoly[2]);
 
 	// Clip the cmd_16bit to avoid wrapping
-	if cmd_16bit > 60000
-		cmd_16bit = 60000
-	else if cmd_16bit < 2000
-		cmd_16bit = 0
+	if (cmd_16bit > 60000)
+		cmd_16bit = 60000;
+	else if (cmd_16bit < 2000)
+		cmd_16bit = 0;
 
 	// Return the result
 	return cmd_16bit;	
diff --git a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
index d9983fb2..1b64bf0e 100644
--- a/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
+++ b/dfall_ws/src/dfall_pkg/src/nodes/StudentControllerService.cpp
@@ -51,13 +51,13 @@
 
 // VARIABLES FOR VALUES LOADED FROM THE YAML FILE
 // > the proportional gain for z control
-float yaml_kp_z = 1.0 
+float yaml_kp_z = 1.0;
 
 // > the derivative gain for z control
-float yaml_kd_z = 1.0
+float yaml_kd_z = 1.0;
 
 // > the integral gain for z control
-float yaml_ki_z = 1.0
+float yaml_ki_z = 1.0;
 
 
 
@@ -322,7 +322,7 @@ bool calculateControlOutput(Controller::Request &request, Controller::Response &
 
 	// Put the computed thrust adjustment into the "response" variable.
 	// > On top of the thrust adjustment, we must add the feed-forward thrust
-+	//   to counter-act gravity.
+	//   to counter-act gravity.
 	// > NOTE: remember that the thrust is commanded per motor, so you sohuld
 	//         consider whether the "thrustAdjustment" computed by your
 	//         controller needed to be divided by 4 or not.
-- 
GitLab