建造属于你的无人驾驶车——(十七)导航-ARBOTIX仿真器+RVIZ

建造属于你的无人驾驶车!
本专栏持续更新中…
程序源码:https://github.com/kkmd66/ZZX_RUN
Solidworks模型文件:https://github.com/kkmd66/ZZX_RUN/releases/tag/ZZX_RUN_Solidworks

导航-ARBOTIX仿真器+RVIZ

第一步,创建fake_zzx_run_arbotix.yaml配置文件

文件位置:zzx_run_bingup/config/fake_zzx_run_arbotix.yaml

port: /dev/ttyUSB0
baud: 115200
rate: 20
sync_write: True
sync_read: True
read_rate: 20
write_rate: 20

controllers: {
   #  Pololu motors: 1856 cpr = 0.3888105m travel = 4773 ticks per meter (empirical: 4100)
   base_controller: {type: diff_controller, base_frame_id: base_footprint, base_width: 0.26, ticks_meter: 4100, Kp: 12, Kd: 12, Ki: 0, Ko: 50, accel_limit: 1.0 }
}

第二步,创建fake_zzx_run_robot启动文件

文件位置:zzx_run_bingup/config/fake_zzx_run_robot.launch

<launch>

    <param name="/use_sim_time" value="false" />

    <!-- 加载机器人Xacro模型 -->
    <arg name="urdf_file" default="$(find xacro)/xacro --inorder '$(find zzx_run_gazebo)/urdf/zzx_run_robot.urdf.xacro'" />

    <param name="robot_description" command="$(arg urdf_file)" />

    <node name="arbotix" pkg="arbotix_python" type="arbotix_driver" output="screen" clear_params="true">
        <rosparam file="$(find zzx_run_bringup)/config/fake_zzx_run_arbotix.yaml" command="load" />
        <param name="sim" value="true"/>
    </node>

    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher">
        <param name="publish_frequency" type="double" value="20.0" />
    </node>

</launch>

第三步,创建导航启动文件

文件位置:zzx_run_navigation/launch/fake_navigation.launch

<launch>

    <param name="use_sim_time" value="false" />

    <!-- 设置地图的配置文件 -->
    <arg name="map" default="map.yaml" />

    <!-- 运行地图服务器,并且加载设置的地图-->
    <node name="map_server" pkg="map_server" type="map_server" args="$(find zzx_run_navigation)/maps/$(arg map)"/>

    <!-- 运行move_base节点 -->
    <include file="$(find zzx_run_navigation)/launch/fake_move_base.launch" />

    <!-- 运行虚拟定位,兼容AMCL输出 -->
    <node pkg="fake_localization" type="fake_localization" name="fake_localization" output="screen" />

    <!-- 对于虚拟定位,需要设置一个/odom与/map之间的静态坐标变换 -->
    <node pkg="tf" type="static_transform_publisher" name="map_odom_broadcaster" args="0 0 0 0 0 0 /map /odom 100" />

    <!-- 运行rviz -->
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find zzx_run_navigation)/rviz/navigation.rviz"/>

</launch>

启动

roslaunch zzx_run_bringup fake_zzx_run_robot.launch
roslaunch zzx_run_navigation fake_navigation.launch

效果

在这里插入图片描述

最后

有问题可以和我联系~
在这里插入图片描述

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值