Closed y2d2 closed 1 year ago
I gave a wrong error message in the previous log it gave the following error message:
Could not transform base_link to odom: Could not find a connection between 'odom' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees..
anyways. Since I did 'hack away` a lot the recent days, I decided to start fresh with 1 robot today:
turtlebot4_standard_humble_1.0.0.zip
I downloaded on the 10th of July and resized the sd card.sudo apt-get update && sudo apt-get upgrade -y
ros2 launch turtlebot4_navigation localization.launch.py map=:./map.yaml
with ./map.yaml a custom build map I directly got the message Could not transform base_link to odom: Could not find a connection between 'odom' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees..
ros2 topic echo /odom
as normal stayed blank for some time but then comes through and published the odom. However the TF tree remained the same. /odom
topic. #!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from tf2_ros import TransformBroadcaster
from geometry_msgs.msg import TransformStamped
from nav_msgs.msg import Odometry
class FramePublisher(Node):
def __init__(self):
super().__init__('tf_odom_base_link')
self.subscription = self.create_subscription(Odometry, "odom", self.update_o_bl_tf, 10)
def update_o_bl_tf(self, msg):
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'odom'
t.child_frame_id = 'base_link'
t.transform.translation.x = msg.pose.pose.position.x
t.transform.translation.y = msg.pose.pose.position.y
t.transform.translation.z = msg.pose.pose.position.z
t.transform.rotation.x = msg.pose.pose.orientation.x
t.transform.rotation.y = msg.pose.pose.orientation.y
t.transform.rotation.z = msg.pose.pose.orientation.z
t.transform.rotation.w = msg.pose.pose.orientation.w
self.tf_broadcaster.sendTransform(t)
def main(args=None):
rclpy.init(args=args)
node = FramePublisher()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
[WARN] [1690903785.216893707] [tf_map_odom]: New publisher discovered on topic 'odom', offering incompatible QoS. No messages will be received from it. Last incompatible policy: RELIABILITY
/odom
topic (Maybe this is the reason why in the past the odom base_link tf
was not very stable and now maybe through some update is not working at all? (However, this seems like a create3 issue I suppose?)
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from tf2_ros import TransformBroadcaster from geometry_msgs.msg import TransformStamped from nav_msgs.msg import Odometry
from rclpy.qos import QoSProfile, QoSReliabilityPolicy, QoSHistoryPolicy
class FramePublisher(Node): def init(self): super().init('tf_odom_base_link') qos_profile = QoSProfile( reliability=QoSReliabilityPolicy.BEST_EFFORT, history=QoSHistoryPolicy.KEEP_LAST, depth=1 ) self.subscription = self.create_subscription(Odometry, "odom", self.update_o_bl_tf, qos_profile=qos_profile)
def update_o_bl_tf(self, msg):
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'odom'
t.child_frame_id = 'base_link'
t.transform.translation.x = msg.pose.pose.position.x
t.transform.translation.y = msg.pose.pose.position.y
t.transform.translation.z = msg.pose.pose.position.z
t.transform.rotation.x = msg.pose.pose.orientation.x
t.transform.rotation.y = msg.pose.pose.orientation.y
t.transform.rotation.z = msg.pose.pose.orientation.z
t.transform.rotation.w = msg.pose.pose.orientation.w
self.tf_broadcaster.sendTransform(t)
def main(args=None): rclpy.init(args=args) node = FramePublisher() rclpy.spin(node) node.destroy_node() rclpy.shutdown()
- which resolved the issue and the tf was broadcasted.
- Now I tried to change the namespace (I did not try the new TF broadcaster here since now I ran into another issue: the oakd-pro stops after few seconds when the namespace is used (not the case when no namespace is used), I am not sure if this was also the case last week. So maybe has to do with the updates as well.
- I made a small shell script to monitor the topic list on my controlling PC:
count=1 while true; do
echo "check $count for ROS_DOMAIN_ID=$ROS_DOMAIN_ID and RMW=$RMW_IMPLEMENTATION"
count=$(expr $count + 1)
ros2 topic list;
sleep 2;
echo "-------------------------------------------------------------------------"
done
Running this while the TB rebooted showed the following results:
- At check 103 we see the topics from the create3 (I think) emerge
- At check 112 I think we start to see the rPI topics emerge
- at check 115 the oakd topics are emerging.
- At check 124 the oakd topics have ceased to exist.
Here are some of the checks:
Tomorrow I will take note of the versions of the distribution and do the same without the `sudo apt-get full-upgrade -y' with the other TB4 and report on the results.
On the OAKD issue Actually, it was a none issue. The robot was docked when I was using the namespace and you guys are probably tired of explaining https://github.com/turtlebot/turtlebot4/issues/193 that when the TB is docked the camera switches off. I apologize for this.
Odom baseline tf with namespace The workaround provided in the previous comment seems to work well when using a namespace as well.
I am currently updating the other TB similar to the previous comment and will report the different steps here (although I am not sure if they are still relevant.)
Concerning the RPi upgrade It seems everything works now on both TBs without the need of the workaround. (Maybe I needed an additional reboot?) I'm wondering however which node is actually publishing the odom base_link transform? I thought it would be a node on the create3, but seems like it is the AMCL which does it? '
Anyways here are the different outputs regarding the upgrade and full-upgrade, which apparently did not make much difference.
The output of sudo apt-get upgrade
on a freshly flashed RPi:
sudo apt-get upgrade
Reading package lists... Done
Building dependency tree... Done
Reading state information... Done
Calculating upgrade... Done
The following packages have been kept back:
linux-headers-raspi linux-image-raspi linux-raspi ros-humble-depthai-examples ros-humble-depthai-ros-driver ros-humble-navigation2 ros-humble-ros2-controllers ros-humble-turtlebot4-description ufw
The following packages will be upgraded:
alsa-ucm-conf apparmor apport apt apt-utils bind9-dnsutils bind9-host bind9-libs binutils binutils-aarch64-linux-gnu binutils-common ca-certificates cloud-init cpp-11 curl distro-info-data
dnsmasq-base dpkg dpkg-dev flash-kernel fwupd-signed g++-11 gcc-11 gcc-11-base gcc-12-base gfortran-11 ghostscript git git-man graphicsmagick-libmagick-dev-compat initramfs-tools initramfs-tools-bin
initramfs-tools-core iptables krb5-multidev libapparmor1 libapt-pkg6.0 libasan6 libatomic1 libavahi-client3 libavahi-common-data libavahi-common3 libbinutils libcap2 libcap2-bin libcc1-0 libctf-nobfd0
libctf0 libcups2 libcurl3-gnutls libcurl4 libcurl4-openssl-dev libdpkg-perl libegl-mesa0 libegl1-mesa-dev libfreetype-dev libfreetype6 libfreetype6-dev libfwupd2 libfwupdplugin5 libgbm-dev libgbm1
libgcc-11-dev libgcc-s1 libgfortran-11-dev libgfortran5 libgl1-mesa-dev libgl1-mesa-dri libglapi-mesa libglib2.0-0 libglib2.0-bin libglib2.0-data libglib2.0-dev libglib2.0-dev-bin libglx-mesa0
libgomp1 libgraphics-magick-perl libgraphicsmagick++-q16-12 libgraphicsmagick++1-dev libgraphicsmagick-q16-3 libgraphicsmagick1-dev libgs9 libgs9-common libgssapi-krb5-2 libgssrpc4 libhwasan0 libidn12
libinput-bin libinput10 libip4tc2 libip6tc2 libitm1 libk5crypto3 libkadm5clnt-mit12 libkadm5srv-mit12 libkdb5-10 libkrb5-3 libkrb5-dev libkrb5support0 libldap-2.5-0 libldap-common libllvm15 liblsan0
libmm-glib0 libmysqlclient21 libncurses-dev libncurses5-dev libncurses6 libncursesw6 libnetplan0 libnss-systemd libpam-cap libpam-systemd libpcsclite1 libperl5.34 libpq5 libprotobuf23 libpulse-dev
libpulse-mainloop-glib0 libpulse0 libpython3.10 libpython3.10-dev libpython3.10-minimal libpython3.10-stdlib librsvg2-2 librsvg2-common libsasl2-2 libsasl2-modules libsasl2-modules-db libssh-4
libssh-gcrypt-4 libssl-dev libssl3 libstdc++-11-dev libstdc++6 libsystemd0 libtiff-dev libtiff5 libtiffxx5 libtinfo6 libtsan0 libubsan1 libudev-dev libudev1 libwebp-dev libwebp7 libwebpdemux2
libwebpmux3 libx11-6 libx11-data libx11-dev libx11-xcb1 libxml2 libxml2-dev libxml2-utils libxtables12 linux-firmware linux-libc-dev mdadm mesa-va-drivers mesa-vdpau-drivers mesa-vulkan-drivers
modemmanager ncurses-base ncurses-bin ncurses-term netplan.io open-vm-tools openssh-client openssh-server openssh-sftp-server openssl perl perl-base perl-modules-5.34 python3-apport python3-debian
python3-distutils python3-gdbm python3-lib2to3 python3-problem-report python3-requests python3-rosdep python3-rosdep-modules python3-rospkg-modules python3-software-properties python3-tz python3.10
python3.10-dev python3.10-minimal ros-humble-ackermann-msgs ros-humble-action-msgs ros-humble-actionlib-msgs ros-humble-admittance-controller ros-humble-ament-cmake ros-humble-ament-cmake-auto
ros-humble-ament-cmake-copyright ros-humble-ament-cmake-core ros-humble-ament-cmake-cppcheck ros-humble-ament-cmake-cpplint ros-humble-ament-cmake-export-definitions
ros-humble-ament-cmake-export-dependencies ros-humble-ament-cmake-export-include-directories ros-humble-ament-cmake-export-interfaces ros-humble-ament-cmake-export-libraries
ros-humble-ament-cmake-export-link-flags ros-humble-ament-cmake-export-targets ros-humble-ament-cmake-flake8 ros-humble-ament-cmake-gen-version-h ros-humble-ament-cmake-gmock
ros-humble-ament-cmake-gtest ros-humble-ament-cmake-include-directories ros-humble-ament-cmake-libraries ros-humble-ament-cmake-lint-cmake ros-humble-ament-cmake-pep257 ros-humble-ament-cmake-pytest
ros-humble-ament-cmake-python ros-humble-ament-cmake-ros ros-humble-ament-cmake-target-dependencies ros-humble-ament-cmake-test ros-humble-ament-cmake-uncrustify ros-humble-ament-cmake-version
ros-humble-ament-cmake-xmllint ros-humble-ament-copyright ros-humble-ament-cppcheck ros-humble-ament-cpplint ros-humble-ament-flake8 ros-humble-ament-index-cpp ros-humble-ament-index-python
ros-humble-ament-lint ros-humble-ament-lint-auto ros-humble-ament-lint-cmake ros-humble-ament-lint-common ros-humble-ament-pep257 ros-humble-ament-uncrustify ros-humble-ament-xmllint ros-humble-angles
ros-humble-backward-ros ros-humble-behaviortree-cpp-v3 ros-humble-bond ros-humble-bondcpp ros-humble-builtin-interfaces ros-humble-camera-calibration ros-humble-camera-calibration-parsers
ros-humble-camera-info-manager ros-humble-class-loader ros-humble-common-interfaces ros-humble-composition-interfaces ros-humble-compressed-depth-image-transport ros-humble-compressed-image-transport
ros-humble-console-bridge-vendor ros-humble-control-msgs ros-humble-control-toolbox ros-humble-controller-interface ros-humble-costmap-queue ros-humble-cv-bridge ros-humble-cyclonedds
ros-humble-depth-image-proc ros-humble-depthai ros-humble-depthai-bridge ros-humble-depthai-ros-msgs ros-humble-diagnostic-aggregator ros-humble-diagnostic-msgs ros-humble-diagnostic-updater
ros-humble-diff-drive-controller ros-humble-domain-coordinator ros-humble-dwb-core ros-humble-dwb-critics ros-humble-dwb-msgs ros-humble-dwb-plugins ros-humble-effort-controllers
ros-humble-eigen3-cmake-module ros-humble-fastcdr ros-humble-fastrtps ros-humble-fastrtps-cmake-module ros-humble-filters ros-humble-foonathan-memory-vendor ros-humble-force-torque-sensor-broadcaster
ros-humble-forward-command-controller ros-humble-foxglove-msgs ros-humble-generate-parameter-library ros-humble-generate-parameter-library-py ros-humble-geometry-msgs ros-humble-geometry2
ros-humble-gmock-vendor ros-humble-gtest-vendor ros-humble-hardware-interface ros-humble-iceoryx-binding-c ros-humble-iceoryx-hoofs ros-humble-iceoryx-posh ros-humble-ignition-cmake2-vendor
ros-humble-ignition-math6-vendor ros-humble-image-geometry ros-humble-image-pipeline ros-humble-image-proc ros-humble-image-publisher ros-humble-image-rotate ros-humble-image-transport
ros-humble-image-transport-plugins ros-humble-image-view ros-humble-imu-sensor-broadcaster ros-humble-interactive-markers ros-humble-irobot-create-control ros-humble-irobot-create-description
ros-humble-irobot-create-msgs ros-humble-joint-state-broadcaster ros-humble-joint-trajectory-controller ros-humble-joy ros-humble-joy-linux ros-humble-kdl-parser ros-humble-keyboard-handler
ros-humble-kinematics-interface ros-humble-laser-geometry ros-humble-launch ros-humble-launch-ros ros-humble-launch-testing ros-humble-launch-testing-ament-cmake ros-humble-launch-testing-ros
ros-humble-launch-xml ros-humble-launch-yaml ros-humble-libcurl-vendor ros-humble-libstatistics-collector ros-humble-libyaml-vendor ros-humble-lifecycle-msgs ros-humble-map-msgs
ros-humble-message-filters ros-humble-nav-2d-msgs ros-humble-nav-2d-utils ros-humble-nav-msgs ros-humble-nav2-amcl ros-humble-nav2-behavior-tree ros-humble-nav2-behaviors ros-humble-nav2-bringup
ros-humble-nav2-bt-navigator ros-humble-nav2-collision-monitor ros-humble-nav2-common ros-humble-nav2-constrained-smoother ros-humble-nav2-controller ros-humble-nav2-core ros-humble-nav2-costmap-2d
ros-humble-nav2-dwb-controller ros-humble-nav2-lifecycle-manager ros-humble-nav2-map-server ros-humble-nav2-msgs ros-humble-nav2-navfn-planner ros-humble-nav2-planner
ros-humble-nav2-regulated-pure-pursuit-controller ros-humble-nav2-rotation-shim-controller ros-humble-nav2-rviz-plugins ros-humble-nav2-simple-commander ros-humble-nav2-smac-planner
ros-humble-nav2-smoother ros-humble-nav2-theta-star-planner ros-humble-nav2-util ros-humble-nav2-velocity-smoother ros-humble-nav2-voxel-grid ros-humble-nav2-waypoint-follower ros-humble-ompl
ros-humble-orocos-kdl-vendor ros-humble-osrf-pycommon ros-humble-parameter-traits ros-humble-pluginlib ros-humble-position-controllers ros-humble-pybind11-vendor ros-humble-python-cmake-module
ros-humble-rcl ros-humble-rcl-action ros-humble-rcl-interfaces ros-humble-rcl-lifecycle ros-humble-rcl-logging-interface ros-humble-rcl-logging-spdlog ros-humble-rcl-yaml-param-parser
ros-humble-rclcpp ros-humble-rclcpp-action ros-humble-rclcpp-components ros-humble-rclcpp-lifecycle ros-humble-rclpy ros-humble-rcpputils ros-humble-rcutils ros-humble-realtime-tools
ros-humble-resource-retriever ros-humble-rmw ros-humble-rmw-cyclonedds-cpp ros-humble-rmw-dds-common ros-humble-rmw-fastrtps-cpp ros-humble-rmw-fastrtps-shared-cpp ros-humble-rmw-implementation
ros-humble-rmw-implementation-cmake ros-humble-robot-state-publisher ros-humble-robot-upstart ros-humble-ros-base ros-humble-ros-core ros-humble-ros-environment ros-humble-ros-workspace
ros-humble-ros2action ros-humble-ros2bag ros-humble-ros2cli ros-humble-ros2cli-common-extensions ros-humble-ros2component ros-humble-ros2doctor ros-humble-ros2interface ros-humble-ros2launch
ros-humble-ros2lifecycle ros-humble-ros2multicast ros-humble-ros2node ros-humble-ros2param ros-humble-ros2pkg ros-humble-ros2run ros-humble-ros2service ros-humble-ros2topic ros-humble-rosbag2
ros-humble-rosbag2-compression ros-humble-rosbag2-compression-zstd ros-humble-rosbag2-cpp ros-humble-rosbag2-interfaces ros-humble-rosbag2-py ros-humble-rosbag2-storage
ros-humble-rosbag2-storage-default-plugins ros-humble-rosbag2-transport ros-humble-rosgraph-msgs ros-humble-rosidl-adapter ros-humble-rosidl-cli ros-humble-rosidl-cmake
ros-humble-rosidl-default-generators ros-humble-rosidl-default-runtime ros-humble-rosidl-generator-c ros-humble-rosidl-generator-cpp ros-humble-rosidl-generator-py ros-humble-rosidl-parser
ros-humble-rosidl-runtime-c ros-humble-rosidl-runtime-cpp ros-humble-rosidl-runtime-py ros-humble-rosidl-typesupport-c ros-humble-rosidl-typesupport-cpp ros-humble-rosidl-typesupport-fastrtps-c
ros-humble-rosidl-typesupport-fastrtps-cpp ros-humble-rosidl-typesupport-interface ros-humble-rosidl-typesupport-introspection-c ros-humble-rosidl-typesupport-introspection-cpp ros-humble-rplidar-ros
ros-humble-rpyutils ros-humble-rsl ros-humble-rviz-assimp-vendor ros-humble-rviz-common ros-humble-rviz-default-plugins ros-humble-rviz-imu-plugin ros-humble-rviz-ogre-vendor ros-humble-rviz-rendering
ros-humble-sdl2-vendor ros-humble-sensor-msgs ros-humble-sensor-msgs-py ros-humble-shape-msgs ros-humble-shared-queues-vendor ros-humble-simple-term-menu-vendor ros-humble-slam-toolbox
ros-humble-smclib ros-humble-spdlog-vendor ros-humble-sqlite3-vendor ros-humble-sros2 ros-humble-sros2-cmake ros-humble-statistics-msgs ros-humble-std-msgs ros-humble-std-srvs
ros-humble-stereo-image-proc ros-humble-stereo-msgs ros-humble-tcb-span ros-humble-teleop-twist-joy ros-humble-tf2 ros-humble-tf2-bullet ros-humble-tf2-eigen ros-humble-tf2-eigen-kdl
ros-humble-tf2-geometry-msgs ros-humble-tf2-kdl ros-humble-tf2-msgs ros-humble-tf2-py ros-humble-tf2-ros ros-humble-tf2-ros-py ros-humble-tf2-sensor-msgs ros-humble-tf2-tools
ros-humble-theora-image-transport ros-humble-tinyxml-vendor ros-humble-tinyxml2-vendor ros-humble-tl-expected ros-humble-tracetools ros-humble-tracetools-image-pipeline ros-humble-trajectory-msgs
ros-humble-tricycle-controller ros-humble-turtlebot4-base ros-humble-turtlebot4-bringup ros-humble-turtlebot4-diagnostics ros-humble-turtlebot4-msgs ros-humble-turtlebot4-navigation
ros-humble-turtlebot4-node ros-humble-turtlebot4-robot ros-humble-turtlebot4-setup ros-humble-turtlebot4-tests ros-humble-uncrustify-vendor ros-humble-unique-identifier-msgs ros-humble-urdf
ros-humble-urdf-parser-plugin ros-humble-urdfdom ros-humble-urdfdom-headers ros-humble-velocity-controllers ros-humble-vision-msgs ros-humble-visualization-msgs ros-humble-xacro
ros-humble-yaml-cpp-vendor ros-humble-zstd-vendor rsync snapd software-properties-common sudo systemd systemd-hwe-hwdb systemd-sysv tcpdump tzdata ubuntu-advantage-tools ubuntu-minimal ubuntu-server
ubuntu-server-raspi ubuntu-standard udev update-notifier-common vim vim-common vim-runtime vim-tiny xxd
529 upgraded, 0 newly installed, 0 to remove and 9 not upgraded.
Need to get 531 MB of archives.
After this operation, 13.4 MB of additional disk space will be used.
Do you want to continue? [Y/n]
So these packages for some reason are kept back:
linux-headers-raspi linux-image-raspi linux-raspi ros-humble-depthai-examples ros-humble-depthai-ros-driver ros-humble-navigation2 ros-humble-ros2-controllers ros-humble-turtlebot4-description ufw
I tried the ros2 launch turtlebot4_navigation localization.launch.py map:=/sharedDrive/map/map_name.yaml
now and this works.
Did the full-upgrade:
sudo apt-get full-upgrade
Reading package lists... Done
Building dependency tree... Done
Reading state information... Done
Calculating upgrade... Done
The following NEW packages will be installed:
libbenchmark-dev libbenchmark1 libllvm14 libomp-14-dev libomp-dev libomp5-14 libxsimd-dev
libxtensor-dev ros-humble-ackermann-steering-controller ros-humble-bicycle-steering-controller
ros-humble-depthai-descriptions ros-humble-joint-state-publisher ros-humble-nav2-mppi-controller
ros-humble-steering-controllers-library ros-humble-tricycle-steering-controller xtl-dev
The following packages have been kept back:
ufw
The following packages will be upgraded:
ros-humble-depthai-examples ros-humble-depthai-ros-driver ros-humble-navigation2
ros-humble-ros2-controllers ros-humble-turtlebot4-description
5 upgraded, 16 newly installed, 0 to remove and 1 not upgraded.
Need to get 74.3 MB of archives.
After this operation, 201 MB of additional disk space will be used.
Do you want to continue? [Y/n]
After the upgrade the version of different packages I thought were interesting are:
ros2 launch turtlebot4_navigation localization.launch.py map:=/sharedDrive/map/map_name.yaml
which worked as well. So although I am not sure what went wrong everything seems to work as expected using the fastDDS, I will not try out the cycloneDDS again so for me all is good.
sorry forgot to push the 'close with comment' button.
Please provide the following information:
sudo dpkg -s ros-$ROS_VERSION-turtlebot4-PACKAGE_WITH_ISSUE
, but it should besudo dpkg -s ros-$ROS_DISTRO-turtlebot4-PACKAGE_WITH_ISSUE
? at least so it is on my system.)Create3 firmware: H2.2
Expected behaviour When I connect 2 TBs using https://github.com/turtlebot/turtlebot4/issues/132 and run the localization and navigation stack for both of them I expect the TBs to work.
Actual behaviour As long as the localization and navigation of neither is running everything seems fine. The moment I start one of them most of the time it works, however, I noticed that the /odom topic and others of the other TB start to stop providing updates. The moment I start this localization and navigation of the second TB it is unreactive and is waiting for the /odom to /base_link transformation:
[controller_server-1] [INFO] [1690835508.615078609] [tb2.local_costmap.local_costmap]: Timed out waiting for transform from base_link to odom to become available, tf error: Invalid frame ID "base_link" passed to canTransform argument source_frame - frame does not exist
Sometimes the other robots' navigation will also stop with the same issue or pause for long times with this message before continuing.The create3 log gives the following info:
[tb1.system_health]: Discovered 78 nodes! Considering using DOMAIN_ID to reduce the burden on the application Jul 31 13:49:49 iRobot-623CE57328134F83A5B4314DF6EBB89D user.notice ntpd: ntpd: reply from 192.168.186.3: delay 0.002503 is too high, ignoring Jul 31 13:50:32 iRobot-623CE57328134F83A5B4314DF6EBB89D user.notice create-platform: [INFO] [1690811432.968177493] [tb1.system_health]: CPU usage: max 99 [%] mean 98 [%] RAM usage: 39/59
which makes me believe that the create3 platform cannot handle that many nodes. See https://github.com/turtlebot/turtlebot4/issues/234 for more details of what I tried to get it to work.
To Reproduce Provide the steps to reproduce:
ros2 launch turtlebot4_navigation localization.launch.py namespace:=tb1 map=:./map.yaml
with ./map.yaml a custom build map, but can be any map, and the navigation stackros2 launch turtlebot4_navigation nav2.launch.py namespace:=tb1
Other notes I made a more detailed description (https://github.com/turtlebot/turtlebot4/issues/234) of the things I tried to make it work but did not make it a bug report and cannot figure out how to change it.