From d9a4493506878e8fa631e6323c7b8d4f2a9ad3af Mon Sep 17 00:00:00 2001
From: Angel <roangel@student.ethz.ch>
Date: Wed, 20 Sep 2017 18:17:53 +0200
Subject: [PATCH] tried to fix it?

---
 pps_ws/src/d_fall_pps/param/Crazyflie.db       | 3 ++-
 pps_ws/src/d_fall_pps/src/FollowN_1Service.cpp | 4 +++-
 2 files changed, 5 insertions(+), 2 deletions(-)

diff --git a/pps_ws/src/d_fall_pps/param/Crazyflie.db b/pps_ws/src/d_fall_pps/param/Crazyflie.db
index 2a9b92bf..7e90e6d4 100644
--- a/pps_ws/src/d_fall_pps/param/Crazyflie.db
+++ b/pps_ws/src/d_fall_pps/param/Crazyflie.db
@@ -1 +1,2 @@
-1,PPS_CF01,0/0/2M,0,-1.11965,0.674688,-0.2,-0.475825,1.29008,2
+1,PPS_CF02,0/8/2M/E7E7E7E702,0,-1.38022,-0.405516,-0.2,-0.481301,0.485645,2
+2,PPS_CF04,0/24/2M,1,-0.412714,-0.376959,-0.2,0.423148,0.384735,2
diff --git a/pps_ws/src/d_fall_pps/src/FollowN_1Service.cpp b/pps_ws/src/d_fall_pps/src/FollowN_1Service.cpp
index 67e4800c..1e097efd 100644
--- a/pps_ws/src/d_fall_pps/src/FollowN_1Service.cpp
+++ b/pps_ws/src/d_fall_pps/src/FollowN_1Service.cpp
@@ -49,6 +49,7 @@ float prevEstimate[9];
 std::vector<float>  setpoint(4);
 float saturationThrust;
 ros::Publisher followPublisher;
+ros::Subscriber followSubscriber;
 
 CrazyflieData previousLocation;
 
@@ -209,6 +210,7 @@ void followCallback(const Setpoint& newSetpoint) {
     setpoint[1] = newSetpoint.y;
     setpoint[2] = newSetpoint.z;
     setpoint[3] = newSetpoint.yaw;
+    ROS_INFO("received callback new setpoint from FollowN1Service/FollowTopic");
 }
 
 
@@ -232,7 +234,7 @@ int main(int argc, char* argv[]) {
     if(student_id != 1)
     {
         // subscribe to n-1 setpoint
-        ros::Subscriber followSubscriber = nodeHandle.subscribe("/" + std::to_string(student_id - 1) + "/FollowN_1Service/FollowTopic", 1, followCallback);
+        followSubscriber = nodeHandle.subscribe("/" + std::to_string(student_id - 1) + "/FollowN_1Service/FollowTopic", 1, followCallback);
     }
     else
     {
-- 
GitLab