File tree Expand file tree Collapse file tree 1 file changed +49
-0
lines changed
Expand file tree Collapse file tree 1 file changed +49
-0
lines changed Original file line number Diff line number Diff line change 1+ #!/usr/bin/env python3
2+
3+ import rclpy
4+ from rclpy .node import Node
5+ from nav_msgs .msg import Odometry
6+ from scipy .spatial .transform import Rotation
7+
8+ class OdomHeadingSubscriber (Node ):
9+ def __init__ (self ):
10+ super ().__init__ ('odom_heading_subscriber' )
11+ self .subscription = self .create_subscription (
12+ Odometry ,
13+ '/glider/odom' ,
14+ self .odom_callback ,
15+ 10 )
16+ self .get_logger ().info ('Odometry heading subscriber initialized' )
17+
18+ def odom_callback (self , msg ):
19+ # Extract quaternion from odometry message
20+ orientation = msg .pose .pose .orientation
21+ quat = [orientation .x , orientation .y , orientation .z , orientation .w ]
22+
23+ # Convert quaternion to Euler angles using scipy
24+ rotation = Rotation .from_quat (quat )
25+ euler = rotation .as_euler ('xyz' , degrees = False )
26+
27+ # Extract yaw (rotation around z-axis)
28+ yaw = euler [2 ]
29+
30+ # Convert radians to degrees
31+ heading_degrees = yaw * 180.0 / 3.141592653589793
32+
33+ # Print the heading
34+ self .get_logger ().info (f'Heading: { heading_degrees :.2f} degrees' )
35+
36+ def main (args = None ):
37+ rclpy .init (args = args )
38+ node = OdomHeadingSubscriber ()
39+
40+ try :
41+ rclpy .spin (node )
42+ except KeyboardInterrupt :
43+ pass
44+ finally :
45+ node .destroy_node ()
46+ rclpy .shutdown ()
47+
48+ if __name__ == '__main__' :
49+ main ()
You can’t perform that action at this time.
0 commit comments