ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Directly looking at your tf tree you can say that something is wrong : you should have all your frames connected with each other. The most surprising thing is the frame base_footprint
not connected with anything, yet you didn't defined it.
The issue is inside <include file="$(find ydlidar)/launch/lidar.launch" />
if you look at the content of lidar.launch
here there is this node launched too :
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
args="0.2245 0.0 0.2 0.0 0.0 0.0 /base_footprint /laser_frame 40" />
This node does the work for you to set the static transform base_footprint -> laser_frame
but then you redifine a new parent to laser_frame
:
<node pkg="tf" type="static_transform_publisher" name="base_frame_laser"
args="0.0 0.0 0.0 0 0 0.0 /base_link /laser_frame 40" />
You have two options here :
lidar.launch
only copy/paste the ydlidar node and params part to put it in your launch file (ie removing the static_transform_publisher
node)base_link -> laser_frame
change it to base_link -> base_footprint
.2 | No.2 Revision |
Directly looking at your tf tree you can say that something is wrong : you should have all your frames connected with each other. The most surprising thing is the frame base_footprint
not connected with anything, yet you didn't defined it.
The issue is inside <include file="$(find ydlidar)/launch/lidar.launch" />
if you look at the content of lidar.launch
here there is this node launched too :
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
args="0.2245 0.0 0.2 0.0 0.0 0.0 /base_footprint /laser_frame 40" />
This node does the work for you to set the static transform base_footprint -> laser_frame
but then you redifine a new parent to laser_frame
:
<node pkg="tf" type="static_transform_publisher" name="base_frame_laser"
args="0.0 0.0 0.0 0 0 0.0 /base_link /laser_frame 40" />
You have two options here :
lidar.launch
only copy/paste the ydlidar node and params part to put it in your launch file (ie removing the static_transform_publisher
node)base_link -> laser_frame
change it to base_link -> base_footprint
.EDIT:
You have inverted the frames, map
is the parent of odom
. Your launch file should be :
<launch>
<include file="$(find ydlidar)/launch/lidar.launch" />
<node pkg="tf" type="static_transform_publisher" name="map_to_odom"
args="0.0 0.0 0.0 0 0 0.0 /map /odom 40" />
<node pkg="tf" type="static_transform_publisher" name="odom_to_baselink"
args="0.0 0.0 0.0 0 0 0.0 /odom /base_link 40" />
<node pkg="tf" type="static_transform_publisher" name="base_frame_laser"
args="0.0 0.0 0.0 0 0 0.0 /base_link /base_footprint 40" />
<include file="$(find hector_mapping)/launch/mapping_default.launch" />
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ydlidar)/launch/lidar.rviz" />
<include file="$(find hector_geotiff)/launch/geotiff_mapper.launch" />
</launch>
3 | No.3 Revision |
Directly looking at your tf tree you can say that something is wrong : you should have all your frames connected with each other. The most surprising thing is the frame base_footprint
not connected with anything, yet you didn't defined it.
The issue is inside <include file="$(find ydlidar)/launch/lidar.launch" />
if you look at the content of lidar.launch
here there is this node launched too :
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
args="0.2245 0.0 0.2 0.0 0.0 0.0 /base_footprint /laser_frame 40" />
This node does the work for you to set the static transform base_footprint -> laser_frame
but then you redifine a new parent to laser_frame
:
<node pkg="tf" type="static_transform_publisher" name="base_frame_laser"
args="0.0 0.0 0.0 0 0 0.0 /base_link /laser_frame 40" />
You have two options here :
lidar.launch
only copy/paste the ydlidar node and params part to put it in your launch file (ie removing the static_transform_publisher
node)base_link -> laser_frame
change it to base_link -> base_footprint
.EDIT:
You have inverted the frames, map
is the parent of odom
. Your launch file should be :
<launch>
<include file="$(find ydlidar)/launch/lidar.launch" />
<node name="ydlidar_node" pkg="ydlidar" type="ydlidar_node" output="screen">
<param name="port" type="string" value="/dev/ydlidar"/>
<param name="baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser_frame"/>
<param name="angle_fixed" type="bool" value="true"/>
<param name="low_exposure" type="bool" value="false"/>
<param name="heartbeat" type="bool" value="false"/>
<param name="resolution_fixed" type="bool" value="true"/>
<param name="angle_min" type="double" value="-180" />
<param name="angle_max" type="double" value="180" />
<param name="range_min" type="double" value="0.08" />
<param name="range_max" type="double" value="16.0" />
<param name="ignore_array" type="string" value="" />
<param name="samp_rate" type="int" value="9"/>
<param name="frequency" type="double" value="7"/>
</node>
<node pkg="tf" type="static_transform_publisher" name="map_to_odom"
args="0.0 0.0 0.0 0 0 0.0 /map /odom 40" />
<node pkg="tf" type="static_transform_publisher" name="odom_to_baselink" name="odom_to_basefootprint"
args="0.0 0.0 0.0 0 0 0.0 /odom /base_footprint 40" />
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link"
args="0.0 0.0 0.0 0 0 0.0 /base_footprint /base_link 40" />
<node pkg="tf" type="static_transform_publisher" name="base_frame_laser"
name="base_link_to_laser"
args="0.0 0.0 0.0 0 0 0.0 /base_link /base_footprint /laser_frame 40" />
<include file="$(find hector_mapping)/launch/mapping_default.launch" />
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ydlidar)/launch/lidar.rviz" />
<include file="$(find hector_geotiff)/launch/geotiff_mapper.launch" />
</launch>
4 | No.4 Revision |
Directly looking at your tf tree you can say that something is wrong : you should have all your frames connected with each other. The most surprising thing is the frame base_footprint
not connected with anything, yet you didn't defined it.
The issue is inside <include file="$(find ydlidar)/launch/lidar.launch" />
if you look at the content of lidar.launch
here there is this node launched too :
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
args="0.2245 0.0 0.2 0.0 0.0 0.0 /base_footprint /laser_frame 40" />
This node does the work for you to set the static transform base_footprint -> laser_frame
but then you redifine a new parent to laser_frame
:
<node pkg="tf" type="static_transform_publisher" name="base_frame_laser"
args="0.0 0.0 0.0 0 0 0.0 /base_link /laser_frame 40" />
You have two options here :
lidar.launch
only copy/paste the ydlidar node and params part to put it in your launch file (ie removing the static_transform_publisher
node)base_link -> laser_frame
change it to base_link -> base_footprint
.EDIT:
You have inverted the frames, map
is the parent of odom
. Your launch file should be :
<launch>
<node name="ydlidar_node" pkg="ydlidar" type="ydlidar_node" output="screen">
<param name="port" type="string" value="/dev/ydlidar"/>
<param name="baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser_frame"/>
<param name="angle_fixed" type="bool" value="true"/>
<param name="low_exposure" type="bool" value="false"/>
<param name="heartbeat" type="bool" value="false"/>
<param name="resolution_fixed" type="bool" value="true"/>
<param name="angle_min" type="double" value="-180" />
<param name="angle_max" type="double" value="180" />
<param name="range_min" type="double" value="0.08" />
<param name="range_max" type="double" value="16.0" />
<param name="ignore_array" type="string" value="" />
<param name="samp_rate" type="int" value="9"/>
<param name="frequency" type="double" value="7"/>
</node>
<node pkg="tf" type="static_transform_publisher" name="map_to_odom"
args="0.0 0.0 0.0 0 0 0.0 /map /odom 40" />
<node pkg="tf" type="static_transform_publisher" name="odom_to_basefootprint"
args="0.0 0.0 0.0 0 0 0.0 /odom /base_footprint 40" />
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link"
args="0.0 0.0 0.0 0 0 0.0 /base_footprint /base_link 40" />
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser"
args="0.0 0.0 0.0 0 0 0.0 /base_link /laser_frame 40" />
<include file="$(find hector_mapping)/launch/mapping_default.launch" />
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ydlidar)/launch/lidar.rviz" />
<include file="$(find hector_geotiff)/launch/geotiff_mapper.launch" />
</launch>
I've removed the <include file="$(find ydlidar)/launch/lidar.launch" />
because you hsould have map -> odom -> base_footprint -> base_link -> laser_frame
instead of map -> odom -> base_link -> base_footprint -> laser_frame
.
5 | No.5 Revision |
Directly looking at your tf tree you can say that something is wrong : you should have all your frames connected with each other. The most surprising thing is the frame base_footprint
not connected with anything, yet you didn't defined it.
The issue is inside <include file="$(find ydlidar)/launch/lidar.launch" />
if you look at the content of lidar.launch
here there is this node launched too :
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser4"
args="0.2245 0.0 0.2 0.0 0.0 0.0 /base_footprint /laser_frame 40" />
This node does the work for you to set the static transform base_footprint -> laser_frame
but then you redifine a new parent to laser_frame
:
<node pkg="tf" type="static_transform_publisher" name="base_frame_laser"
args="0.0 0.0 0.0 0 0 0.0 /base_link /laser_frame 40" />
You have two options here :
lidar.launch
only copy/paste the ydlidar node and params part to put it in your launch file (ie removing the static_transform_publisher
node)base_link -> laser_frame
change it to base_link -> base_footprint
.EDIT:
You have inverted the frames, map
is the parent of odom
. Your launch file should be :
<launch>
<node name="ydlidar_node" pkg="ydlidar" type="ydlidar_node" output="screen">
<param name="port" type="string" value="/dev/ydlidar"/>
<param name="baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser_frame"/>
<param name="angle_fixed" type="bool" value="true"/>
<param name="low_exposure" type="bool" value="false"/>
<param name="heartbeat" type="bool" value="false"/>
<param name="resolution_fixed" type="bool" value="true"/>
<param name="angle_min" type="double" value="-180" />
<param name="angle_max" type="double" value="180" />
<param name="range_min" type="double" value="0.08" />
<param name="range_max" type="double" value="16.0" />
<param name="ignore_array" type="string" value="" />
<param name="samp_rate" type="int" value="9"/>
<param name="frequency" type="double" value="7"/>
</node>
<node pkg="tf" type="static_transform_publisher" name="map_to_odom"
args="0.0 0.0 0.0 0 0 0.0 /map /odom 40" />
<node pkg="tf" type="static_transform_publisher" name="odom_to_basefootprint"
args="0.0 0.0 0.0 0 0 0.0 /odom /base_footprint 40" />
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link"
args="0.0 0.0 0.0 0 0 0.0 /base_footprint /base_link 40" />
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser"
args="0.0 0.0 0.0 0 0 args="0.2245 0.0 0.2 0.0 0.0 0.0 /base_link /laser_frame 40" />
<include file="$(find hector_mapping)/launch/mapping_default.launch" />
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ydlidar)/launch/lidar.rviz" />
<include file="$(find hector_geotiff)/launch/geotiff_mapper.launch" />
</launch>
I've removed the <include file="$(find ydlidar)/launch/lidar.launch" />
because you hsould have map -> odom -> base_footprint -> base_link -> laser_frame
instead of map -> odom -> base_link -> base_footprint -> laser_frame
.