publish_cam.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # ==============================================================================
4 # MIT License
5 #
6 # Copyright (c) 2023-2025 Institute for Automotive Engineering (ika), RWTH Aachen University
7 #
8 # Permission is hereby granted, free of charge, to any person obtaining a copy
9 # of this software and associated documentation files (the "Software"), to deal
10 # in the Software without restriction, including without limitation the rights
11 # to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12 # copies of the Software, and to permit persons to whom the Software is
13 # furnished to do so, subject to the following conditions:
14 #
15 # The above copyright notice and this permission notice shall be included in all
16 # copies or substantial portions of the Software.
17 #
18 # THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19 # IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20 # FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21 # AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22 # LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
23 # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
24 # SOFTWARE.
25 # ==============================================================================
26 
27 import rclpy
28 from rclpy.node import Node
29 from etsi_its_cam_msgs.msg import *
30 import utils
31 
32 
33 class Publisher(Node):
34 
35  def __init__(self):
36 
37  super().__init__("cam_publisher")
38  topic = "/etsi_its_conversion/cam/in"
39  self.publisher = self.create_publisher(CAM, topic, 1)
40  self.timer = self.create_timer(0.1, self.publish)
41 
42  def publish(self):
43 
44  msg = CAM()
45 
46  msg.header.protocol_version = 2
47  msg.header.message_id = msg.header.MESSAGE_ID_CAM
48  msg.header.station_id.value = 32
49 
50  msg.cam.generation_delta_time.value = int(utils.get_t_its(self.get_clock().now().nanoseconds) % 65536)
51 
52  msg.cam.cam_parameters.basic_container.station_type.value = msg.cam.cam_parameters.basic_container.station_type.PASSENGER_CAR
53  msg.cam.cam_parameters.basic_container.reference_position.latitude.value = int(msg.cam.cam_parameters.basic_container.reference_position.latitude.ONE_MICRODEGREE_NORTH * 1e6 * 50.787369)
54  msg.cam.cam_parameters.basic_container.reference_position.longitude.value = int(msg.cam.cam_parameters.basic_container.reference_position.longitude.ONE_MICRODEGREE_EAST * 1e6 * 6.046504)
55 
56  basic_vehicle_container_high_frequency = BasicVehicleContainerHighFrequency()
57  basic_vehicle_container_high_frequency.heading.heading_value.value = basic_vehicle_container_high_frequency.heading.heading_value.WGS84_NORTH
58  basic_vehicle_container_high_frequency.heading.heading_confidence.value = basic_vehicle_container_high_frequency.heading.heading_confidence.EQUAL_OR_WITHIN_ONE_DEGREE
59  basic_vehicle_container_high_frequency.speed.speed_value.value = basic_vehicle_container_high_frequency.speed.speed_value.ONE_CENTIMETER_PER_SEC
60  basic_vehicle_container_high_frequency.speed.speed_confidence.value = basic_vehicle_container_high_frequency.speed.speed_confidence.EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC
61  basic_vehicle_container_high_frequency.vehicle_length.vehicle_length_value.value = basic_vehicle_container_high_frequency.vehicle_length.vehicle_length_value.TEN_CENTIMETERS * 42
62  basic_vehicle_container_high_frequency.vehicle_width.value = basic_vehicle_container_high_frequency.vehicle_width.TEN_CENTIMETERS * 18
63  msg.cam.cam_parameters.high_frequency_container.choice = msg.cam.cam_parameters.high_frequency_container.CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY
64  msg.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency = basic_vehicle_container_high_frequency
65 
66  self.get_logger().info(f"Publishing CAM")
67  self.publisher.publish(msg)
68 
69 
70 if __name__ == "__main__":
71 
72  rclpy.init()
73  publisher = Publisher()
74  rclpy.spin(publisher)
75  rclpy.shutdown()
utils.get_t_its
def get_t_its(unix_nanoseconds)
Definition: utils.py:30
publish_cam.Publisher.__init__
def __init__(self)
Definition: publish_cam.py:35
publish_cam.Publisher.timer
timer
Definition: publish_cam.py:40
publish_cam.Publisher
Definition: publish_cam.py:33
msg
publish_cam.Publisher.publish
def publish(self)
Definition: publish_cam.py:42
publish_cam.Publisher.publisher
publisher
Definition: publish_cam.py:39


etsi_its_msgs_utils
Author(s): Jean-Pierre Busch , Guido Küppers , Lennart Reiher
autogenerated on Sun May 18 2025 02:32:12