Skip to content

Commit d0d9135

Browse files
Specification on catching TransformException
1 parent 1630447 commit d0d9135

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

kf_hungarian_tracker/kf_hungarian_tracker/kf_hungarian_node.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
import colorsys
1111
from kf_hungarian_tracker.obstacle_class import ObstacleClass
1212

13+
from tf2_ros import TransformException
1314
from tf2_ros.buffer import Buffer
1415
from tf2_ros.transform_listener import TransformListener
1516
from tf2_geometry_msgs import do_transform_point, do_transform_vector3
@@ -119,7 +120,7 @@ def callback(self, msg):
119120
s.vector = detections[i].size
120121
detections[i].size = do_transform_vector3(s, trans).vector
121122

122-
except Exception as ex:
123+
except TransformException as ex:
123124
self.get_logger().error(
124125
'fail to get tf from {} to {}: {}'.format(
125126
msg.header.frame_id, self.global_frame, ex))

0 commit comments

Comments
 (0)