代码拉取完成,页面将自动刷新
同步操作将从 冰达机器人/robot_navigation 强制同步,此操作会覆盖自 Fork 仓库以来所做的任何修改,且无法恢复!!!
确定后同步将在后台操作,完成时将刷新页面,请耐心等待。
<launch>
<!--robot bast type use different tf value-->
<arg name="base_type" default="$(env BASE_TYPE)" />
<!-- robot frame -->
<arg name="base_frame" default="/base_footprint" />
<arg name="lidar_type" default="$(env LIDAR_TYPE)" />
<arg name="lidar_frame" default="base_laser_link"/>
<include file="$(find robot_navigation)/launch/lidar/$(arg lidar_type).launch">
<arg name="lidar_frame" value="$(arg lidar_frame)"/>
</include>
<group if="$(eval base_type == 'NanoRobot')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="-0.01225 0.0 0.18 3.14159265 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
<group if="$(eval base_type == 'NanoRobot_Pro')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="-0.0515 0.0 0.18 -1.5708 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
<group if="$(eval base_type == '4WD')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="0.01 0.0 0.25 3.14159265 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
<group if="$(eval base_type == '4WD_OMNI')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="0.01 0.0 0.25 3.14159265 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
<group if="$(eval base_type == 'NanoCar')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="0.1037 0.0 0.115 3.14159265 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
<group if="$(eval base_type == 'NanoCar_Pro')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="0.1037 0.0 0.165 3.14159265 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
<group if="$(eval base_type == 'NanoCar_SE')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="0.0955 0.0 0.115 1.5708 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
<group if="$(eval base_type == 'Race182')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="0.1 0.0 0.192 3.14159265 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
<group if="$(eval base_type == 'NanoOmni')">
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_laser"
args="0.019 0.0 0.192 3.14159265 0.0 0.0 $(arg base_frame) $(arg lidar_frame) 20">
</node>
</group>
</launch>
此处可能存在不合适展示的内容,页面不予展示。您可通过相关编辑功能自查并修改。
如您确认内容无涉及 不当用语 / 纯广告导流 / 暴力 / 低俗色情 / 侵权 / 盗版 / 虚假 / 无价值内容或违法国家有关法律法规的内容,可点击提交进行申诉,我们将尽快为您处理。