|
12 | 12 | # See the License for the specific language governing permissions and
|
13 | 13 | # limitations under the License.
|
14 | 14 |
|
| 15 | +import builtins |
15 | 16 | import copy
|
16 | 17 |
|
17 | 18 | import pytest
|
18 | 19 |
|
| 20 | +from builtin_interfaces.msg import Time |
19 | 21 | from rosidl_runtime_py import set_message_fields
|
| 22 | +from std_msgs.msg import Header |
20 | 23 | from test_msgs import message_fixtures
|
| 24 | +import rosidl_parser.definition |
| 25 | + |
| 26 | + |
| 27 | +class MockMessageStamped: |
| 28 | + |
| 29 | + __slots__ = [ |
| 30 | + '_header', |
| 31 | + ] |
| 32 | + |
| 33 | + _fields_and_field_types = { |
| 34 | + 'header': 'std_msgs/Header', |
| 35 | + } |
| 36 | + |
| 37 | + SLOT_TYPES = ( |
| 38 | + rosidl_parser.definition.NamespacedType(['std_msgs', 'msg'], 'Header'), |
| 39 | + ) |
| 40 | + |
| 41 | + def __init__(self): |
| 42 | + self.header = Header() |
| 43 | + |
| 44 | + @builtins.property |
| 45 | + def header(self): |
| 46 | + return self._header |
| 47 | + |
| 48 | + @header.setter |
| 49 | + def header(self, value): |
| 50 | + self._header = value |
| 51 | + |
| 52 | + |
| 53 | +class MockMessageWithStampFields: |
| 54 | + |
| 55 | + __slots__ = [ |
| 56 | + '_timestamp1', |
| 57 | + '_timestamp2', |
| 58 | + ] |
| 59 | + |
| 60 | + _fields_and_field_types = { |
| 61 | + 'timestamp1': 'builtin_interfaces/Time', |
| 62 | + 'timestamp2': 'builtin_interfaces/Time', |
| 63 | + } |
| 64 | + |
| 65 | + SLOT_TYPES = ( |
| 66 | + rosidl_parser.definition.NamespacedType(['builtin_interfaces', 'msg'], 'Time'), |
| 67 | + rosidl_parser.definition.NamespacedType(['builtin_interfaces', 'msg'], 'Time'), |
| 68 | + ) |
| 69 | + |
| 70 | + def __init__(self): |
| 71 | + self.timestamp1 = Time() |
| 72 | + self.timestamp2 = Time() |
| 73 | + |
| 74 | + @builtins.property |
| 75 | + def timestamp1(self): |
| 76 | + return self._timestamp1 |
| 77 | + |
| 78 | + @timestamp1.setter |
| 79 | + def timestamp1(self, value): |
| 80 | + self._timestamp1 = value |
| 81 | + |
| 82 | + @builtins.property |
| 83 | + def timestamp2(self): |
| 84 | + return self._timestamp2 |
| 85 | + |
| 86 | + @timestamp2.setter |
| 87 | + def timestamp2(self, value): |
| 88 | + self._timestamp2 = value |
21 | 89 |
|
22 | 90 |
|
23 | 91 | def test_set_message_fields_none():
|
@@ -148,3 +216,63 @@ def test_set_message_fields_nested_type():
|
148 | 216 | set_message_fields(msg0, test_values)
|
149 | 217 |
|
150 | 218 | assert msg0.basic_types_value == msg_basic_types
|
| 219 | + |
| 220 | + |
| 221 | +def test_set_message_fields_header_auto(): |
| 222 | + msg = MockMessageStamped() |
| 223 | + values = {'header': 'auto'} |
| 224 | + assert msg.header.stamp.sec == 0 and msg.header.stamp.nanosec == 0 |
| 225 | + assert msg.header.frame_id == '' |
| 226 | + timestamp_fields = set_message_fields( |
| 227 | + msg, values, expand_header_auto=True, expand_time_now=True) |
| 228 | + assert timestamp_fields is not None |
| 229 | + for field_setter in timestamp_fields: |
| 230 | + stamp = Time(sec=1, nanosec=2) |
| 231 | + field_setter(stamp) |
| 232 | + assert msg.header.stamp.sec == 1 and msg.header.stamp.nanosec == 2 |
| 233 | + assert msg.header.frame_id == '' |
| 234 | + |
| 235 | + |
| 236 | +def test_set_message_fields_stamp_now(): |
| 237 | + msg = MockMessageStamped() |
| 238 | + values = {'header': {'stamp': 'now'}} |
| 239 | + assert msg.header.stamp.sec == 0 and msg.header.stamp.nanosec == 0 |
| 240 | + assert msg.header.frame_id == '' |
| 241 | + timestamp_fields = set_message_fields( |
| 242 | + msg, values, expand_header_auto=True, expand_time_now=True) |
| 243 | + assert timestamp_fields is not None |
| 244 | + for field_setter in timestamp_fields: |
| 245 | + stamp = Time(sec=1, nanosec=2) |
| 246 | + field_setter(stamp) |
| 247 | + assert msg.header.stamp.sec == 1 and msg.header.stamp.nanosec == 2 |
| 248 | + assert msg.header.frame_id == '' |
| 249 | + |
| 250 | + |
| 251 | +def test_set_message_fields_stamp_now_with_frame_id(): |
| 252 | + msg = MockMessageStamped() |
| 253 | + values = {'header': {'stamp': 'now', 'frame_id': 'hello'}} |
| 254 | + assert msg.header.stamp.sec == 0 and msg.header.stamp.nanosec == 0 |
| 255 | + assert msg.header.frame_id == '' |
| 256 | + timestamp_fields = set_message_fields( |
| 257 | + msg, values, expand_header_auto=True, expand_time_now=True) |
| 258 | + assert timestamp_fields is not None |
| 259 | + for field_setter in timestamp_fields: |
| 260 | + stamp = Time(sec=1, nanosec=2) |
| 261 | + field_setter(stamp) |
| 262 | + assert msg.header.stamp.sec == 1 and msg.header.stamp.nanosec == 2 |
| 263 | + assert msg.header.frame_id == 'hello' |
| 264 | + |
| 265 | + |
| 266 | +def test_set_message_fields_stamp_now_with_timestamp_fields(): |
| 267 | + msg = MockMessageWithStampFields() |
| 268 | + values = {'timestamp1': 'now', 'timestamp2': 'now'} |
| 269 | + assert msg.timestamp1.sec == 0 and msg.timestamp1.nanosec == 0 |
| 270 | + assert msg.timestamp2.sec == 0 and msg.timestamp2.nanosec == 0 |
| 271 | + timestamp_fields = set_message_fields( |
| 272 | + msg, values, expand_header_auto=True, expand_time_now=True) |
| 273 | + assert timestamp_fields is not None |
| 274 | + for field_setter in timestamp_fields: |
| 275 | + stamp = Time(sec=1, nanosec=2) |
| 276 | + field_setter(stamp) |
| 277 | + assert msg.timestamp1.sec == 1 and msg.timestamp1.nanosec == 2 |
| 278 | + assert msg.timestamp2.sec == 1 and msg.timestamp2.nanosec == 2 |
0 commit comments