Skip to content

Commit b173e0d

Browse files
mergify[bot]bjsowa
andauthored
fix: Auto-populate header.stamp when header omitted (backport #1220) (#1223)
* fix: Auto-populate header.stamp when header omitted (#1220) * docs: Clarify special handling of time fields * Add tests for header and time fields population * fix: Auto-populate header.stamp when header omitted * fix: Validate header type in populate_instance function (cherry picked from commit 42ce055) * Add type ignore for header attribute --------- Co-authored-by: Błażej Sowa <bsowa123@gmail.com>
1 parent 9677edb commit b173e0d

File tree

3 files changed

+154
-9
lines changed

3 files changed

+154
-9
lines changed

ROSBRIDGE_PROTOCOL.md

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -312,7 +312,8 @@ The operation fails if the `msg` does not conform to the type of the topic.
312312
Special cases for how the server handles the `msg` field:
313313

314314
- If the `msg` does not contain all fields for the topic type, then the unspecified fields are filled in with defaults.
315-
- If the topic type has a `header` field of type `std_msgs/Header` and the client omits the `header.stamp` field, then the server will automatically populate it with the current ROS time.
315+
- If the topic type has a root `header` field of type `std_msgs/Header` and the client omits the `header.stamp` field, then the server will automatically populate it with the current ROS time.
316+
- If the topic type has any field of type `builtin_interfaces/Time` and the client sets that field to `"now"` string, then the server will automatically populate it with the current ROS time.
316317

317318
**Server → Client**
318319

rosbridge_library/src/rosbridge_library/internal/message_conversion.py

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,6 @@
9999
"double",
100100
"string",
101101
)
102-
ros_header_types = ("Header", "std_msgs/Header", "roslib/Header")
103102
ros_binary_types = ("uint8[]", "char[]", "sequence<uint8>", "sequence<char>")
104103
# Remove the list type wrapper, and length specifier, from rostypes i.e. sequence<double, 3>
105104
list_tokens = re.compile(r"<(.+?)(, \d+)?>")
@@ -206,6 +205,19 @@ def populate_instance(
206205

207206
inst_type = msg_instance_type_repr(inst)
208207

208+
# Auto-populate header.stamp when the root message has a "header" field of type std_msgs/Header
209+
# and the client omitted the header entirely or omitted only the stamp.
210+
inst_fields = inst.get_fields_and_field_types()
211+
if inst_fields.get("header") == "std_msgs/Header":
212+
header_msg = msg.get("header")
213+
if header_msg is not None and not isinstance(header_msg, dict):
214+
raise FieldTypeMismatchException(inst_type, ["header"], "dict", type(header_msg))
215+
if header_msg is None or "stamp" not in header_msg:
216+
assert hasattr(inst, "header")
217+
header_inst = inst.header # type: ignore[attr-defined]
218+
if isinstance(header_inst, HeaderMsg):
219+
header_inst.stamp = clock.now().to_msg()
220+
209221
return _to_object_inst(msg, inst_type, inst_type, clock, inst, [])
210222

211223

@@ -497,13 +509,6 @@ def _to_object_inst(
497509
if not isinstance(msg, dict):
498510
raise FieldTypeMismatchException(roottype, stack, rostype, type(msg))
499511

500-
# Substitute the correct time if we're an std_msgs/Header
501-
if rostype in ros_header_types:
502-
if not isinstance(inst, HeaderMsg):
503-
err_msg = f"inst is not a HeaderMsg, but a {type(inst)}"
504-
raise TypeError(err_msg)
505-
inst.stamp = clock.now().to_msg()
506-
507512
inst_fields: dict[str, str] = inst.get_fields_and_field_types()
508513
for field_name, field_value in msg.items():
509514
# Add this field to the field stack

rosbridge_library/test/capabilities/test_publish.py

Lines changed: 139 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
from typing import Any
99

1010
import rclpy
11+
from geometry_msgs.msg import PoseStamped
1112
from rclpy.executors import SingleThreadedExecutor
1213
from rclpy.node import Node
1314
from rclpy.qos import DurabilityPolicy, QoSProfile
@@ -17,6 +18,7 @@
1718
MissingArgumentException,
1819
)
1920
from rosbridge_library.protocol import Protocol
21+
from sensor_msgs.msg import TimeReference
2022
from std_msgs.msg import String
2123

2224

@@ -74,6 +76,143 @@ def cb(msg: String) -> None:
7476
time.sleep(0.5)
7577
self.assertEqual(received["msg"].data, msg["data"])
7678

79+
def test_publish_header_stamp_auto_populated_when_stamp_omitted(self) -> None:
80+
proto = Protocol("hello", self.node)
81+
pub = Publish(proto)
82+
topic = "/test_header_stamp_auto_populated"
83+
84+
received: dict[str, Any] = {"msg": None}
85+
86+
def cb(msg: PoseStamped) -> None:
87+
received["msg"] = msg
88+
89+
subscriber_qos = QoSProfile(
90+
depth=10,
91+
durability=DurabilityPolicy.TRANSIENT_LOCAL,
92+
)
93+
self.node.create_subscription(PoseStamped, topic, cb, subscriber_qos)
94+
95+
# Publish with header present but stamp omitted
96+
pub_msg = {
97+
"op": "publish",
98+
"topic": topic,
99+
"type": "geometry_msgs/msg/PoseStamped",
100+
"msg": {"header": {}},
101+
}
102+
pub.publish(pub_msg)
103+
time.sleep(0.5)
104+
105+
self.assertIsNotNone(received["msg"])
106+
stamp = received["msg"].header.stamp
107+
self.assertGreater(
108+
stamp.sec + stamp.nanosec,
109+
0,
110+
"Expected server to auto-populate header.stamp with current ROS time, but stamp is zero",
111+
)
112+
113+
def test_publish_header_stamp_preserved_when_provided_by_client(self) -> None:
114+
proto = Protocol("hello", self.node)
115+
pub = Publish(proto)
116+
topic = "/test_header_stamp_preserved"
117+
118+
received: dict[str, Any] = {"msg": None}
119+
120+
def cb(msg: PoseStamped) -> None:
121+
received["msg"] = msg
122+
123+
subscriber_qos = QoSProfile(
124+
depth=10,
125+
durability=DurabilityPolicy.TRANSIENT_LOCAL,
126+
)
127+
self.node.create_subscription(PoseStamped, topic, cb, subscriber_qos)
128+
129+
expected_sec = 12345
130+
expected_nanosec = 67890
131+
pub_msg = {
132+
"op": "publish",
133+
"topic": topic,
134+
"type": "geometry_msgs/msg/PoseStamped",
135+
"msg": {
136+
"header": {
137+
"stamp": {"sec": expected_sec, "nanosec": expected_nanosec},
138+
}
139+
},
140+
}
141+
pub.publish(pub_msg)
142+
time.sleep(0.5)
143+
144+
self.assertIsNotNone(received["msg"])
145+
stamp = received["msg"].header.stamp
146+
self.assertEqual(stamp.sec, expected_sec)
147+
self.assertEqual(stamp.nanosec, expected_nanosec)
148+
149+
def test_publish_header_stamp_auto_populated_when_header_omitted(self) -> None:
150+
proto = Protocol("hello", self.node)
151+
pub = Publish(proto)
152+
topic = "/test_header_stamp_auto_populated_no_header"
153+
154+
received: dict[str, Any] = {"msg": None}
155+
156+
def cb(msg: PoseStamped) -> None:
157+
received["msg"] = msg
158+
159+
subscriber_qos = QoSProfile(
160+
depth=10,
161+
durability=DurabilityPolicy.TRANSIENT_LOCAL,
162+
)
163+
self.node.create_subscription(PoseStamped, topic, cb, subscriber_qos)
164+
165+
# Publish with no header at all (the entire header field is omitted)
166+
pub_msg = {
167+
"op": "publish",
168+
"topic": topic,
169+
"type": "geometry_msgs/msg/PoseStamped",
170+
"msg": {},
171+
}
172+
pub.publish(pub_msg)
173+
time.sleep(0.5)
174+
175+
self.assertIsNotNone(received["msg"])
176+
stamp = received["msg"].header.stamp
177+
self.assertGreater(
178+
stamp.sec + stamp.nanosec,
179+
0,
180+
"Expected server to auto-populate header.stamp even when header is entirely omitted",
181+
)
182+
183+
def test_publish_time_field_now_string_populated(self) -> None:
184+
proto = Protocol("hello", self.node)
185+
pub = Publish(proto)
186+
topic = "/test_time_field_now"
187+
188+
received: dict[str, Any] = {"msg": None}
189+
190+
def cb(msg: TimeReference) -> None:
191+
received["msg"] = msg
192+
193+
subscriber_qos = QoSProfile(
194+
depth=10,
195+
durability=DurabilityPolicy.TRANSIENT_LOCAL,
196+
)
197+
self.node.create_subscription(TimeReference, topic, cb, subscriber_qos)
198+
199+
pub_msg = {
200+
"op": "publish",
201+
"topic": topic,
202+
"type": "sensor_msgs/msg/TimeReference",
203+
"msg": {"time_ref": "now"},
204+
}
205+
pub.publish(pub_msg)
206+
time.sleep(0.5)
207+
208+
self.assertIsNotNone(received["msg"])
209+
time_ref = received["msg"].time_ref
210+
self.assertGreater(
211+
time_ref.sec + time_ref.nanosec,
212+
0,
213+
'Expected server to populate time_ref with current ROS time when set to "now"',
214+
)
215+
77216

78217
if __name__ == "__main__":
79218
unittest.main()

0 commit comments

Comments
 (0)