From 59190e9d42daffbd30699037f37ba61a024368a5 Mon Sep 17 00:00:00 2001 From: cesar Date: Mon, 25 Apr 2022 16:51:49 -0300 Subject: [PATCH] added sonar (topic: /mavros/distance_sensor) --- models/spiri/spiri.sdf | 114 ++++++++++++++++++++++++++++++++++++++++- src/klausen_control.py | 25 ++++++--- 2 files changed, 130 insertions(+), 9 deletions(-) diff --git a/models/spiri/spiri.sdf b/models/spiri/spiri.sdf index 769f9ce..f94ebb4 100644 --- a/models/spiri/spiri.sdf +++ b/models/spiri/spiri.sdf @@ -2,7 +2,7 @@ - 0 0 0 0 -0 3.141 + 0 0 0 0 -0 0 1 0 0.00268 -0.000742 0 -0 0 @@ -408,6 +408,118 @@ gps0_link + + + + 0 0 0 0 1.57 0 + + 0.05 + + 2.08333333333e-07 + 5.20833333333e-07 + 5.20833333333e-07 + + + + 0 0 0 0 0 0 + + + 0.008 + 0.004 + + + + + + + + 10 + true + + + + 1 + 1 + -0 + 0 + + + + 0.06 + 35 + 0.01 + + + gaussian + 0.0 + 0.01 + + + + 0.005 + true + 10 + /mavros/distance_sensor + sonar_link + 0 + ultrasound + + + + + base + sonar_link + base diff --git a/src/klausen_control.py b/src/klausen_control.py index 376c18b..13a88a3 100755 --- a/src/klausen_control.py +++ b/src/klausen_control.py @@ -101,8 +101,10 @@ class Main: # PD Thrust Controller terms # gains for thrust PD Controller - self.Kp = 2.7 - self.Kd = 3 #2 + #self.Kp = 2.7 + #self.Kd = 3 + self.Kp = 2.7 + self.Kd = 3 self.max_a = 14.2 self.max_t = self.drone_m*self.max_a self.R = np.empty([3,3]) # rotation matrix @@ -252,15 +254,22 @@ class Main: # Taeyoung Lee, Melvin Leok, and N. Harris McClamroch self.waypoints_srv_cb() self.error = np.array([[self.dr_pos.position.x - self.xd.x], - [self.dr_pos.position.y - self.xd.y], - [self.dr_pos.position.z - self.xd.z - self.thrust_offset]]) + [self.dr_pos.position.y - self.xd.y], + [self.dr_pos.position.z - self.xd.z - self.thrust_offset]]) - self.R = self.quaternion_rotation_matrix() # determine Rotation Matrix + self.error_vel = self.dr_vel - self.path_vel + + self.R = self.quaternion_rotation_matrix() # determine Rotation Matrix + self.R_e3 = np.array([[self.R.T[2][0]],[self.R.T[2][1]],[self.R.T[2][2]]]) - #thrust = np.dot(np.dot(9.81*self.drone_m,self.e3) - self.Kp*self.error - self.Kd*self.dr_vel.T,self.R.T[2])/self.max_t - thrust_vector = np.dot(np.dot(9.81*self.drone_m,self.e3) - self.Kp*self.error - self.Kd*self.dr_vel.T,self.R.T[2])/self.max_t - thrust = thrust_vector[2] + #thrust = np.dot(np.dot(9.81*self.drone_m,self.e3) - self.Kp*self.error - self.Kd*self.dr_vel,self.R.T[2])/self.max_t + #thrust_vector = np.dot(9.81*self.drone_m*self.e3 - self.Kp*self.error - self.Kd*self.dr_vel,self.R_e3)/self.max_t + #thrust_vector = (9.81*self.drone_m*self.e3 - self.Kp*self.error - self.Kd*self.dr_vel -9.81*self.drone_m*self.path_acc)/self.max_t + thrust_vector = (9.81*self.drone_m - self.Kp*self.error[2] - self.Kd*self.dr_vel[2])/self.max_t + #thrust = thrust_vector[0]*self.R_e3[0] + thrust_vector[1]*self.R_e3[1] + thrust_vector[2]*self.R_e3[2] + thrust = thrust_vector/(math.cos(self.EulerAng[0]*self.EulerAng[1])) + #thrust = thrust_vector[2] # Value needs to be between 0 - 1.0 self.att_targ.thrust = max(0.0,min(thrust,1.0))