diff --git a/ros_gz_sim_demos/config/magnetometer.yaml b/ros_gz_sim_demos/config/magnetometer.yaml index 3af2e370..e5d38d2e 100644 --- a/ros_gz_sim_demos/config/magnetometer.yaml +++ b/ros_gz_sim_demos/config/magnetometer.yaml @@ -1,9 +1,6 @@ # Magnetometer configuration. -- ros_topic_name: "/magnetometer" - gz_topic_name: "/magnetometer" +- topic_name: "/magnetometer" ros_type_name: "sensor_msgs/msg/MagneticField" gz_type_name: "gz.msgs.Magnetometer" - subscriber_queue: 5 - publisher_queue: 6 - lazy: false + lazy: true direction: GZ_TO_ROS diff --git a/ros_gz_sim_demos/launch/magnetometer.launch.xml b/ros_gz_sim_demos/launch/magnetometer.launch.xml index 065e57da..10639b43 100644 --- a/ros_gz_sim_demos/launch/magnetometer.launch.xml +++ b/ros_gz_sim_demos/launch/magnetometer.launch.xml @@ -1,6 +1,12 @@ - - + +