1717import rclpy .publisher
1818import rclpy .qos
1919import rclpy .subscription
20- from builtin_interfaces .msg import Time
21- from geometry_msgs .msg import Vector3Stamped
22- from sensor_msgs .msg import Imu
20+ from builtin_interfaces .msg import Time as TimeMsg
21+ from geometry_msgs .msg import Vector3Stamped as Vector3StampedMsg
22+ from sensor_msgs .msg import Imu as ImuMsg
2323
2424from oasis_control .localization .tilt_pose_estimator import ImuCalibration
2525from oasis_control .localization .tilt_pose_estimator import TiltPoseEstimator
@@ -117,15 +117,15 @@ def __init__(self) -> None:
117117 )
118118
119119 self ._tilt_pub : rclpy .publisher .Publisher = self .create_publisher (
120- msg_type = Imu ,
120+ msg_type = ImuMsg ,
121121 topic = tilt_topic ,
122122 qos_profile = qos_profile ,
123123 )
124124
125125 self ._tilt_rp_pub : Optional [rclpy .publisher .Publisher ] = None
126126 if publish_tilt_rp :
127127 self ._tilt_rp_pub = self .create_publisher (
128- msg_type = Vector3Stamped ,
128+ msg_type = Vector3StampedMsg ,
129129 topic = f"{ tilt_topic } _rp" ,
130130 qos_profile = qos_profile ,
131131 )
@@ -138,7 +138,7 @@ def __init__(self) -> None:
138138 )
139139
140140 self ._imu_sub : rclpy .subscription .Subscription = self .create_subscription (
141- msg_type = Imu ,
141+ msg_type = ImuMsg ,
142142 topic = imu_topic ,
143143 callback = self ._handle_imu ,
144144 qos_profile = qos_profile ,
@@ -167,11 +167,11 @@ def _handle_calibration(self, message: ImuCalibrationMsg) -> None:
167167
168168 self ._calibration = calibration
169169
170- def _handle_imu (self , message : Imu ) -> None :
170+ def _handle_imu (self , message : ImuMsg ) -> None :
171171 if self ._calibration is None :
172172 return
173173
174- stamp : Time = message .header .stamp
174+ stamp : TimeMsg = message .header .stamp
175175 timestamp : float = float (stamp .sec ) + float (stamp .nanosec ) * 1.0e-9
176176 if self ._last_imu_time is None :
177177 dt_s : float = 0.0
@@ -211,7 +211,7 @@ def _handle_imu(self, message: Imu) -> None:
211211 if not updated :
212212 return
213213
214- tilt_message : Imu = Imu ()
214+ tilt_message : ImuMsg = ImuMsg ()
215215 tilt_message .header .stamp = message .header .stamp
216216 tilt_message .header .frame_id = (
217217 self ._frame_id if self ._frame_id else message .header .frame_id
@@ -246,7 +246,7 @@ def _handle_imu(self, message: Imu) -> None:
246246 roll : float
247247 pitch : float
248248 roll , pitch , _ = self ._estimator .attitude_rpy ()
249- rp_message : Vector3Stamped = Vector3Stamped ()
249+ rp_message : Vector3StampedMsg = Vector3StampedMsg ()
250250 rp_message .header .stamp = message .header .stamp
251251 rp_message .header .frame_id = tilt_message .header .frame_id
252252 rp_message .vector .x = roll
0 commit comments