diff --git a/.gitignore b/.gitignore index eae16d7..e14a7e0 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,6 @@ launch/debug.launch -src/MoCap_*.py +launch/cortex_bridge.launch +src/MoCap_Localization_*.py +src/MocapBridge.py +src/*_client.py *.rviz diff --git a/config/px4_pluginlists.yaml b/config/px4_pluginlists.yaml index 5a97f05..cb3d58a 100644 --- a/config/px4_pluginlists.yaml +++ b/config/px4_pluginlists.yaml @@ -2,9 +2,7 @@ plugin_blacklist: # common - safety_area # extras -- tdr_radio - image_pub -- vibration - distance_sensor - rangefinder - wheel_odometry diff --git a/launch/cortex_bridge.launch b/launch/cortex_bridge.launch index d2b325e..de74779 100644 --- a/launch/cortex_bridge.launch +++ b/launch/cortex_bridge.launch @@ -9,8 +9,8 @@ Launch file to use klausen oscillaton damping ctrl in Gazebo - + + - - + + + + diff --git a/launch/px4.launch b/launch/px4.launch index da9653b..777c00c 100644 --- a/launch/px4.launch +++ b/launch/px4.launch @@ -1,7 +1,7 @@ - + @@ -10,8 +10,8 @@ - - + + diff --git a/src/MoCap_Localization_noTether.py b/src/MoCap_Localization_noTether.py index a0fc3f0..1fcd148 100755 --- a/src/MoCap_Localization_noTether.py +++ b/src/MoCap_Localization_noTether.py @@ -17,7 +17,7 @@ class Main: def __init__(self): # rate(s) - rate = 100 # rate for the publisher method, specified in Hz -- 20 Hz + rate = 120 # rate for the publisher method, specified in Hz -- 20 Hz # Variables needed for testing start self.tstart = rospy.get_time() # Keep track of the start time @@ -99,12 +99,25 @@ class Main: self.drone_pose.pose.orientation.z, self.drone_pose.pose.orientation.w]) + self.q = quaternion_from_euler(self.eul[0],self.eul[1],self.eul[2]) + + offset_yaw = math.pi/2 + q_offset = quaternion_from_euler(0,0,-offset_yaw) + + self.q = quaternion_multiply(self.q,q_offset) + + self.eul = euler_from_quaternion([self.q[0],self.q[1],self.q[2],self.q[3]]) + self.drone_pose.pose.orientation.x = self.q[0] + self.drone_pose.pose.orientation.y = self.q[1] + self.drone_pose.pose.orientation.z = self.q[2] + self.drone_pose.pose.orientation.w = self.q[3] + def FRD_Transform(self): ''' Transforms mocap reading to proper coordinate frame ''' - self.drone_pose = self.buff_pose +# self.drone_pose = self.buff_pose self.drone_pose.header.frame_id = "/map" # self.drone_pose.pose.position.x = 0 @@ -139,7 +152,7 @@ class Main: def bodyPose_cb(self,msg): try: - self.buff_pose = msg + self.drone_pose = msg except ValueError: pass diff --git a/src/MocapBridge.py b/src/MocapBridge.py index 262a533..39136eb 100755 --- a/src/MocapBridge.py +++ b/src/MocapBridge.py @@ -19,7 +19,7 @@ class Main: def __init__(self): # rate(s) - rate = 50 # rate for the publisher method, specified in Hz -- 20 Hz + rate = 30 # rate for the publisher method, specified in Hz -- 20 Hz # Variables needed for testing start self.tstart = rospy.get_time() # Keep track of the start time @@ -135,6 +135,18 @@ class Main: pose.orientation.z, pose.orientation.w]) +# self.q = quaternion_from_euler(self.eul[0],self.eul[1],self.eul[2]) + +# offset_yaw = math.pi/2 +# q_offset = quaternion_from_euler(0,0,offset_yaw) + +# self.q = quaternion_multiply(self.q,q_offset) + +# self.eul = euler_from_quaternion([self.q[0],self.q[1],self.q[2],self.q[3]]) +# self.LabDrone_pose.pose.orientation.x = self.q[0] +# self.LabDrone_pose.pose.orientation.y = self.q[1] +# self.LabDrone_pose.pose.orientation.z = self.q[2] + def FRD_Transform(self): ''' Transforms mocap reading to proper coordinate frame @@ -172,6 +184,7 @@ class Main: def fake_mocap(self): self.LabDrone_pose.header.stamp = rospy.Time.now() + #self.LabDrone_pose.header.stamp.secs = self.LabDrone_pose.header.stamp.secs - self.tstart self.LabDrone_pose.pose.position.x = 0.0 self.LabDrone_pose.pose.position.y = 0.0 self.LabDrone_pose.pose.position.z = 0.5