cartographer-project / cartographer_ros

Provides ROS integration for Cartographer.
Apache License 2.0
1.67k stars 1.21k forks source link

"imu" passed to lookupTransform argument target_frame does not exist. #1630

Open dlee640 opened 3 years ago

dlee640 commented 3 years ago

I have Ouster OS0-32 3D lidar sensor and I am trying to use cartographer on the recorded data.

When I run: roslaunch ouster_slam os0_slam.launch udp_hostname:=169.254.207.33 bag_filename:=/home/slambox/ouster_slam_ws/terrain_test.bag replay:=true metadata:=/home/slambox/ouster_slam_ws/os-992106000190.local.json carto_conf:=/home/slambox/ouster_slam_ws/src/ouster_slam

I get the following output & error:

Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://slambox-NUC10i7FNH:43303/

SUMMARY
========

PARAMETERS
 * /os_node/imu_port: 7503
 * /os_node/lidar_mode: 
 * /os_node/lidar_port: 7502
 * /os_node/metadata: /home/slambox/ous...
 * /os_node/replay: True
 * /os_node/sensor_hostname: 
 * /os_node/udp_dest: 
 * /robot_description: <?xml version="1....
 * /rosdistro: melodic
 * /rosversion: 1.14.10
 * /use_sim_time: True

NODES
  /
    cartographer_node (cartographer_ros/cartographer_node)
    cartographer_occupancy_grid_node (cartographer_ros/cartographer_occupancy_grid_node)
    os_cloud_node (ouster_ros/os_cloud_node)
    os_node (ouster_ros/os_node)
    playbag (rosbag/play)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    rviz (rviz/rviz)

ROS_MASTER_URI=http://localhost:11311

process[os_node-1]: started with pid [17145]
process[os_cloud_node-2]: started with pid [17146]
[ INFO] [1621622603.094390039]: Client version: 0.2.0-dev0+feb4f19-dirty-release
[ INFO] [1621622603.095217059]: Running in replay mode
[ INFO] [1621622603.095494285]: Using lidar_mode: 1024x10
[ INFO] [1621622603.095506968]: OS-0-32-U1 sn: 992106000190 firmware rev: v2.0.0
process[robot_state_publisher-3]: started with pid [17157]
process[cartographer_node-4]: started with pid [17158]
process[cartographer_occupancy_grid_node-5]: started with pid [17159]
process[rviz-6]: started with pid [17165]
process[playbag-7]: started with pid [17167]
[ INFO] [1621622603.153087653]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/ouster_slam_ws/src/ouster_slam/configuration_files/os0_32.lua' for 'os0_32.lua'.
[ INFO] [1621622603.154358778]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/map_builder.lua' for 'map_builder.lua'.
[ INFO] [1621622603.154402913]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/map_builder.lua' for 'map_builder.lua'.
[ INFO] [1621622603.154463547]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/pose_graph.lua' for 'pose_graph.lua'.
[ INFO] [1621622603.154493972]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/pose_graph.lua' for 'pose_graph.lua'.
[ INFO] [1621622603.154607523]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/trajectory_builder.lua' for 'trajectory_builder.lua'.
[ INFO] [1621622603.154638286]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/trajectory_builder.lua' for 'trajectory_builder.lua'.
[ INFO] [1621622603.154688320]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/trajectory_builder_2d.lua' for 'trajectory_builder_2d.lua'.
[ INFO] [1621622603.154718741]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/trajectory_builder_2d.lua' for 'trajectory_builder_2d.lua'.
[ INFO] [1621622603.154829217]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/trajectory_builder_3d.lua' for 'trajectory_builder_3d.lua'.
[ INFO] [1621622603.154860242]: I0521 14:43:23.000000 17158 configuration_file_resolver.cc:41] Found '/home/slambox/cartographer_ws/install_isolated/share/cartographer/configuration_files/trajectory_builder_3d.lua' for 'trajectory_builder_3d.lua'.
[ INFO] [1621622603.159584642]: I0521 14:43:23.000000 17158 map_builder_bridge.cc:135] Added trajectory with ID '0'.
[ WARN] [1621622603.913691987, 1621016795.182051976]: W0521 14:43:23.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622604.115237306, 1621016795.383852877]: W0521 14:43:24.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622604.315800454, 1621016795.585510608]: W0521 14:43:24.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622604.518397713, 1621016795.787241457]: W0521 14:43:24.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622604.719606565, 1621016795.989164656]: W0521 14:43:24.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622604.922069657, 1621016796.190866536]: W0521 14:43:24.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622605.124479307, 1621016796.393125534]: W0521 14:43:25.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622605.325668251, 1621016796.594993195]: W0521 14:43:25.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622605.527442768, 1621016796.796746609]: W0521 14:43:25.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622605.729597476, 1621016796.998497437]: W0521 14:43:25.000000 17158 tf_bridge.cc:52] "imu" passed to lookupTransform argument target_frame does not exist. 
[ WARN] [1621622605.792707697, 1621016797.058989010]: Could not compute submap fading: "map" passed to lookupTransform argument target_frame does not exist. 
...

I am pretty sure that its a problem that can be fixed by modifying frame parameter in .lua or .launch file.

Here is my .lua configuration file

include "map_builder.lua"
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map", --ROS frame ID to use for publishing submaps
  tracking_frame = "imu", --ROS frame ID of the frame tracked by SLAM algorithm
  published_frame = "imu", --ROS frame ID to use as child frame for publishing poses
  odom_frame = "odom", --set to odom of Cartographer is configured to publish odometry, publishes non-loop closed local SLAM result
  provide_odom_frame = true, --configuration for cartographer to publish the local, non-loop closed odom above
  publish_frame_projected_to_2d = false, --if enabled, published pose will be restricted to x,y, and theta
  use_pose_extrapolator = true,
  use_odometry = false, --use when integrated with A1 odom topic
  use_nav_sat = false, --no gps, thus false
  use_landmarks = false,
  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 1,
  lookup_transform_timeout_sec = 0.2, --Timeout in seconds to use for looking up transforms using tf2.
  submap_publish_period_sec = 0.3, --Interval in seconds at which to publish the submap poses, e.g. 0.3 seconds.
  pose_publish_period_sec = 5e-2, --Interval in seconds at which to publish poses, e.g. 5e-3 for a frequency of 200 Hz.
  trajectory_publish_period_sec = 30e-3, --Interval in seconds at which to publish the trajectory markers, e.g. 30e-3 for 30 milliseconds.
  rangefinder_sampling_ratio = 1., --Fixed ratio sampling for range finders messages.
  odometry_sampling_ratio = 1., --Fixed ratio sampling for odometry messages.
  fixed_frame_pose_sampling_ratio = 1., --Fixed ratio sampling for fixed frame messages.
  imu_sampling_ratio = 1., --Fixed ratio sampling for IMU messages.
  landmarks_sampling_ratio = 1., --Fixed ratio sampling for landmarks messages.
}
MAP_BUILDER.use_trajectory_builder_3d = true

TRAJECTORY_BUILDER_3D.min_range = 10. -- minimal distance Point Cloud -> 0.25 ouster specs
TRAJECTORY_BUILDER_3D.max_range = 50. -- maximal distance Point Cloud ->120 ouster specs

--TRAJECTORY_BUILDER_3D.num_accumulated_range_data = 1

--Filter the Point Cloud
--TRAJECTORY_BUILDER_3D.voxel_filter_size = .05

--TRAJECTORY_BUILDER_3D.adaptive_voxel_filter.max_length = 2.
--TRAJECTORY_BUILDER_3D.adaptive_voxel_filter.min_num_points = 100.

-- Filter the motion
--TRAJECTORY_BUILDER_3D.motion_filter.max_time_seconds = 0.0
--TRAJECTORY_BUILDER_3D.motion_filter.max_distance_meters = 0.0
--TRAJECTORY_BUILDER_3D.motion_filter.max_angle_radians = 0.0 -- math.pi/2

--TRAJECTORY_BUILDER_3D.submaps.num_range_data = 50

--Matching of subscans
--TRAJECTORY_BUILDER_3D.ceres_scan_matcher.occupied_space_weight = 1.
--TRAJECTORY_BUILDER_3D.ceres_scan_matcher.occupied_space_weight_0 = 1.
--TRAJECTORY_BUILDER_3D.ceres_scan_matcher.occupied_space_weight_1 = 1.

--TRAJECTORY_BUILDER_3D.ceres_scan_matcher.translation_weight = 1e3
--TRAJECTORY_BUILDER_3D.ceres_scan_matcher.rotation_weight = 1e3

--TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
--TRAJECTORY_BUILDER_3D.real_time_correlative_scan_matcher.linear_search_window = 0.15
--TRAJECTORY_BUILDER_3D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)

--MAP_BUILDER.use_trajectory_builder_2d = false

--MAP_BUILDER.num_background_threads = 12

--Global SLAM

POSE_GRAPH.optimize_every_n_nodes = 0
POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 100
POSE_GRAPH.constraint_builder.min_score = 0.8
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.8
POSE_GRAPH.optimization_problem.huber_scale = 5e2

return options

and here is my .launch file

<launch>
  <param name="/use_sim_time" value="true" />

  <arg name="sensor_hostname" default="" doc="hostname or IP in dotted decimal form of the sensor"/>
  <arg name="udp_dest" default="" doc="hostname or IP where the sensor will send data packets"/>
  <arg name="lidar_port" default="7502" doc="port to which the sensor should send lidar data"/>
  <arg name="imu_port" default="7503" doc="port to which the sensor should send imu data"/>
  <arg name="replay" default="false" doc="do not connect to a sensor; expect /os_node/{lidar,imu}_packets from replay"/>
  <arg name="lidar_mode" default="" doc="resolution and rate: either 512x10, 512x20, 1024x10, 1024x20, or 2048x10"/>
  <arg name="metadata" default="" doc="override default metadata file for replays"/>
  <arg name="viz" default="false" doc="whether to run a simple visualizer"/>
  <arg name="image" default="false" doc="publish range/intensity/ambient image topic"/>
  <arg name="arg bag_filename" default="false" doc="bag for usage "/>

  <arg name="arg carto_conf" default="" doc="FilePath to your cartograppher configuration"/>

  <node pkg="ouster_ros" name="os_node" type="os_node" output="screen" required="true">
    <param name="~/lidar_mode" type="string" value="$(arg lidar_mode)"/>
    <param name="~/replay" value="$(arg replay)"/>
    <param name="~/sensor_hostname" value="$(arg sensor_hostname)"/>
    <param name="~/udp_dest" value="$(arg udp_dest)"/>
    <param name="~/lidar_port" value="$(arg lidar_port)"/>
    <param name="~/imu_port" value="$(arg imu_port)"/>
    <param name="~/metadata" value="$(arg metadata)"/>
  </node>

  <node pkg="ouster_ros" type="os_cloud_node" name="os_cloud_node" output="screen" required="true">
    <remap from="~/os_config" to="/os_node/os_config"/>
    <remap from="~/lidar_packets" to="/os_node/lidar_packets"/>
    <remap from="~/imu_packets" to="/os_node/imu_packets"/>

    <remap from="/os_cloud_node/imu" to="imu"/>
    <remap from="/os_cloud_node/points" to="points2"/>
  </node>

  <param name="robot_description"
         textfile="$(arg carto_conf)/urdf/os_sensor.urdf"/>

  <node name="robot_state_publisher" pkg="robot_state_publisher"
        type="robot_state_publisher" />

  <node name="cartographer_node" pkg="cartographer_ros"
        type="cartographer_node" args="
          -configuration_directory $(arg carto_conf)/configuration_files
          -configuration_basename os0_32.lua"
        output="screen">

  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
        type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

  <node name="rviz" pkg="rviz" type="rviz" required="true"
        args="-d $(arg carto_conf)/configuration_files/demo_3d.rviz" />

  <node name="playbag" pkg="rosbag" type="play"
        args="--clock $(arg bag_filename)" />

Can some one please guide me on what I am doing wrong? I believe

  map_frame = "map", --ROS frame ID to use for publishing submaps
  tracking_frame = "imu", --ROS frame ID of the frame tracked by SLAM algorithm
  published_frame = "imu", --ROS frame ID to use as child frame for publishing poses

this part in .lua file is where the problem is. I have tried using 'base_link' but it doesn't work.

Here is my frames.pdf when I run the corresponding bag file from the lidar data.: Screenshot from 2021-05-21 14-50-52

soorajanilkumar commented 3 years ago

Hi I think the frame_id you provided doesn't match with your TF tree. Try

  map_frame = "map", --ROS frame ID to use for publishing submaps
  tracking_frame = "os_imu", --ROS frame ID of the frame tracked by SLAM algorithm
  published_frame = "os_sensor", --ROS frame ID to use as child frame for publishing poses
dlee640 commented 3 years ago

Thank you for your response. I changed the parameter but I am having hard time visualizing the data. I also get error messages on rviz regarding transformation between map frame and other frames, despite the fact that I have specified static transform between map frame and base_link frame in the launch file (attached below as well). What is the issue? Also, why do I get blurry map image on my rviz?

Screenshot from 2021-05-29 13-42-00

My launch file (Please look at the last lines for static transform between map frame and base_link:

<launch>
  <param name="/use_sim_time" value="true" />

  <arg name="sensor_hostname" default="os-992106000190.local" doc="hostname or IP in dotted decimal form of the sensor"/>
  <arg name="udp_dest" default="169.254.207.33" doc="hostname or IP where the sensor will send data packets"/>
  <arg name="lidar_port" default="7502" doc="port to which the sensor should send lidar data"/>
  <arg name="imu_port" default="7503" doc="port to which the sensor should send imu data"/>
  <arg name="replay" default="false" doc="do not connect to a sensor; expect /os_node/{lidar,imu}_packets from replay"/>
  <arg name="lidar_mode" default="1024x10" doc="resolution and rate: either 512x10, 512x20, 1024x10, 1024x20, or 2048x10"/>
  <arg name="timestamp_mode" default="" doc="method used to timestamp measurements: TIME_FROM_INTERNAL_OSC, TIME_FROM_SYNC_PULSE_IN, TIME_FROM_PTP_1588"/>
  <arg name="metadata" default="/home/slambox/ouster_slam_ws/os-992106000190.local.json" doc="override default metadata file for replays"/>
  <arg name="viz" default="false" doc="whether to run a simple visualizer"/>
  <arg name="image" default="false" doc="publish range/intensity/noise image topic"/>
  <arg name="tf_prefix" default="" doc="namespace for tf transforms"/>

  <arg name="arg carto_conf" default="/home/slambox/ouster_slam_ws/src/ouster_slam" doc="FilePath to your cartograppher configuration"/>

  <node pkg="ouster_ros" name="os_node" type="os_node" output="screen" required="true">
    <param name="~/lidar_mode" type="string" value="$(arg lidar_mode)"/>
    <param name="~/timestamp_mode" type="string" value="$(arg timestamp_mode)"/>
    <param name="~/replay" value="$(arg replay)"/>
    <param name="~/sensor_hostname" value="$(arg sensor_hostname)"/>
    <param name="~/udp_dest" value="$(arg udp_dest)"/>
    <param name="~/lidar_port" value="$(arg lidar_port)"/>
    <param name="~/imu_port" value="$(arg imu_port)"/>
    <param name="~/metadata" value="$(arg metadata)"/>
  </node>

  <node pkg="ouster_ros" type="os_cloud_node" name="os_cloud_node" output="screen" required="true">
    <remap from="~/os_config" to="/os_node/os_config"/>
    <remap from="~/lidar_packets" to="/os_node/lidar_packets"/>
    <remap from="~/imu_packets" to="/os_node/imu_packets"/>
    <param name="~/tf_prefix" value="$(arg tf_prefix)"/>

    <remap from="/os_cloud_node/imu" to="imu"/>
    <remap from="/os_cloud_node/points" to="points2"/>
  </node>

  <param name="robot_description"
         textfile="$(arg carto_conf)/urdf/os_sensor.urdf"/>

  <node name="robot_state_publisher" pkg="robot_state_publisher"
        type="robot_state_publisher" />

  <node name="cartographer_node" pkg="cartographer_ros"
        type="cartographer_node" args="
          -configuration_directory $(arg carto_conf)/configuration_files
          -configuration_basename os0_32.lua"
        output="screen">
  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
        type="cartographer_occupancy_grid_node" args="-resolution 0.1" />

  <node name="rviz" pkg="rviz" type="rviz" required="true"
        args="-d $(arg carto_conf)/configuration_files/demo_3d.rviz" />

  <node pkg="tf" type="static_transform_publisher" name="base_to_map" args="0 0 0 0 0 0 base_link map 100" />

</launch>

My URDF file:

<?xml version="1.0"?>
<!--
  Copyright 2016 The Cartographer Authors
  Licensed under the Apache License, Version 2.0 (the "License");
  you may not use this file except in compliance with the License.
  You may obtain a copy of the License at
       http://www.apache.org/licenses/LICENSE-2.0
  Unless required by applicable law or agreed to in writing, software
  distributed under the License is distributed on an "AS IS" BASIS,
  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  See the License for the specific language governing permissions and
  limitations under the License.
-->

<robot name="os_sensor">

  <material name="orange">
    <color rgba="1.0 0.5 0.2 1" />
  </material>
  <material name="gray">
    <color rgba="0.2 0.2 0.2 1" />
  </material>

  <link name="os_sensor" />

  <link name="base_link" />

  <joint name="sensor_link_joint" type="fixed">
    <parent link="base_link" />
    <child link="os_sensor" />
    <origin xyz="0 0 0" rpy="0 0 0" />
  </joint>

<!-- Published by OS0 -->

<link name="os_imu">
    <visual>
      <origin xyz="0.0 0.0 0.0" />
      <geometry>
        <box size="0.06 0.04 0.02" />
      </geometry>
      <material name="orange" />
    </visual>
</link>

<link name="os_lidar">
    <visual>
      <origin xyz="0.0 0.0 0.0" />
      <geometry>
        <cylinder length="0.07" radius="0.05" />
      </geometry>
      <material name="gray" />
    </visual>
</link>

  <joint name="imu_link_joint" type="fixed">
    <parent link="os_sensor" />
    <child link="os_imu" />
    <origin xyz="0.006253 -0.011775 0.007645" rpy="0 0 0" />
  </joint>

  <joint name="os_link_joint" type="fixed">
    <parent link="os_sensor" />
    <child link="os_lidar" />
    <origin xyz="0.0 0.0 0.03618" rpy="0 0 3.14159" />
  </joint>

</robot>
soorajanilkumar commented 3 years ago

map to base_link frame should not be static. This is the robot pose calculated by the SLAM.

I am not sure why you would use a static publisher for this!? That's what cartogapher is for.