ardupilot
ardupilot copied to clipboard
AP_DDS: null quaternion in /ap/tf_static not accepted by rviz2
Bug report
Issue details
The null quaternion in /ap/tf_static appears to cause issues when passed to rviz2. The quaternion has all fields set to zero:
% ros2 topic echo /ap/tf_static
transforms:
- header:
stamp:
sec: 1713792800
nanosec: 232813000
frame_id: base_link
child_frame_id: GPS_0
transform:
translation:
x: 0.0
y: -0.0
z: -0.0
rotation:
x: 0.0
y: 0.0
z: 0.0
w: 0.0
When the topic is remapped to /tf_static and passed to rviz2 an error is reported:
% ROS_DISCOVERY_SERVER="192.168.1.170:11812" rviz2 --ros-args --remap tf_static:=/ap/tf_static
[INFO] [1713794415.884889952] [rviz2]: Stereo is NOT SUPPORTED
[INFO] [1713794415.884937536] [rviz2]: OpenGl version: 2.1 (GLSL 1.2)
[INFO] [1713794415.921487525] [rviz2]: Stereo is NOT SUPPORTED
Error: TF_NAN_INPUT: Ignoring transform for child_frame_id "GPS_0" from authority "Authority undetectable" because of a nan value in the transform (0.000000 -0.000000 -0.000000) (nan nan nan nan)
at line 242 in /Users/rhys/Code/ros2/humble/ros2-humble/src/ros2/geometry2/tf2/src/buffer_core.cpp
Error: TF_DENORMALIZED_QUATERNION: Ignoring transform for child_frame_id "GPS_0" from authority "Authority undetectable" because of an invalid quaternion in the transform (nan nan nan nan)
at line 259 in /Users/rhys/Code/ros2/humble/ros2-humble/src/ros2/geometry2/tf2/src/buffer_core.cpp
We need to check the ROS 2 convention for a zero quaternion and whether normalisation is required (i.e. w:=1.0).
Publishing an empty TFMessage suggests that normalisation must be applied:
% ros2 topic pub /tf_static tf2_msgs/msg/TFMessage 'transforms: [{header: {frame_id: "map"}, child_frame_id: "base_link"}]' --once
publisher: beginning loop
publishing #1: tf2_msgs.msg.TFMessage(transforms=[geometry_msgs.msg.TransformStamped(header=std_msgs.msg.Header(stamp=builtin_interfaces.msg.Time(sec=0, nanosec=0), frame_id='map'), child_frame_id='base_link', transform=geometry_msgs.msg.Transform(translation=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.0), rotation=geometry_msgs.msg.Quaternion(x=0.0, y=0.0, z=0.0, w=1.0)))])
Version
- master: commit 5a21d0cb8a859b293eea087fb8c9be150c0ca910 (HEAD -> master, upstream/master)
- custom build:
./waf configure --board MatekH743-bdshot --enable-dds --enable-ppp
Platform [ ] All [ ] AntennaTracker [ ] Copter [ x] Plane [ ] Rover [ ] Submarine
Airframe type
Quadplane X
Hardware type
MatekH743-WING v3, RPi4
Logs
N/A