小车底盘的基础上加雷达和摄像头

需求描述:
在前面小车底盘基础之上,添加摄像头和雷达传感器。
结果演示:
在这里插入图片描述
实现分析:

机器人模型由多部件组成,可以将不同组件设置进单独文件,最终通过文件包含实现组件的拼装。

实现流程:

首先编写摄像头和雷达的 xacro 文件

然后再编写一个组合文件,组合底盘、摄像头与雷达

最后,通过 launch 文件启动 Rviz 并显示模型

1.摄像头和雷达 Xacro 文件实现

摄像头 xacro 文件:

<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
    <!-- 摄像头部件 -->
    <!-- 1.参数 -->
    <!-- 
        参数:
            连杆属性:厚度、宽度、高度
            关节属性: x y z
     -->
     <xacro:property name="camera_length" value="0.02" />    <!-- 厚度(x)-->
     <xacro:property name="camera_width" value="0.05" />    <!-- 宽度(y)-->
     <xacro:property name="camera_heighth" value="0.05" />    <!-- 高度(Z)-->
     <xacro:property name="joint_camera_x" value="0.08" />    
     <xacro:property name="joint_camera_y" value="0" />
     <xacro:property name="joint_camera_z" value="${base_length / 2 + camera_heighth / 2}" />
    <!-- 2.设计连杆和关节 -->
    <link name="camera">
        <visual>
            <geometry>
                <box size="${camera_length} ${camera_width} ${camera_heighth}" />
            </geometry>
            <material name="black">
                <color rgba="0 0 0 0.8" />
            </material>
        </visual>
    </link>

    <joint name="camera2base" type="fixed">
        <parent link="base_link" />
        <child link="camera" />
        <origin xyz="${joint_camera_x} ${joint_camera_y} ${joint_camera_z}" rpy="0 0 0" />
    </joint>
</robot>

雷达 xacro 文件:

<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
    <!-- 雷达部件 -->
    <!-- 参数-->
    <!--
        1.支架 
            支架尺寸:半径 高度 
            关节偏移量:x y z
        2.雷达
            雷达尺寸:半径 高度
            关节偏移量:x y z
     -->
     <xacro:property name="suport_radius" value="0.01" />
     <xacro:property name="suport_length" value="0.15" />
     <xacro:property name="laser_radius" value="0.03" />
     <xacro:property name="laser_length" value="0.05" />

     <xacro:property name="joint_suport_x" value="0" />
     <xacro:property name="joint_suport_y" value="0" />
     <!-- z=车体高度/2 + 支架高度/2 -->
     <xacro:property name="joint_suport_z" value="${base_length / 2 + suport_length / 2}" />

     <xacro:property name="joint_laser_x" value="0" />
     <xacro:property name="joint_laser_y" value="0" />
     <!-- z=支架高度/2 + 雷达高度/2 -->
     <xacro:property name="joint_laser_z" value="${suport_length / 2 + laser_length / 2}" />

    <!-- 1.支架 -->
    <link name="suport">
        <visual>
            <geometry>
                <cylinder radius="${suport_radius}" length="${suport_length}" />
            </geometry>
            <material name="yellow">
                <color rgba="0.8 0.5 0.0 0.5" />
            </material>
        </visual>
    </link>

    <joint name="suport2base" type="fixed">
        <parent link="base_link" />
        <child link="suport" />
        <origin xyz="${joint_suport_x} ${joint_suport_y} ${joint_suport_z}" />
    </joint>
    <!-- 2.雷达 -->
    <link name="laser">
        <visual>
            <geometry>
                <cylinder radius="${laser_radius}" length="${laser_length}" />
            </geometry>
            <material name="blue">
                <color rgba="0.3 0.2 0.8 0.5" />
            </material>
        </visual>
    </link>

    <joint name="laser2suport" type="fixed">
        <parent link="suport" />
        <child link="laser" />
        <origin xyz="${joint_laser_x} ${joint_laser_y} ${joint_laser_z}" />
    </joint>
</robot>

2.组合底盘摄像头与雷达的 xacro 文件

<!-- 组合小车底盘与摄像头与雷达 -->
<robot name="my_car_camera" xmlns:xacro="http://wiki.ros.org/xacro">
    <xacro:include filename="my_base.urdf.xacro" />
    <xacro:include filename="my_camera.urdf.xacro" />
    <xacro:include filename="my_laser.urdf.xacro" />
</robot>

3.launch 文件

<launch>
    <param name="robot_description" command="$(find xacro)/xacro $(find demo01_urdf_helloworld)/urdf/xacro/my_base_camera_laser.urdf.xacro" />

    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find demo01_urdf_helloworld)/config/helloworld.rviz" />
    <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen" />
    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen" />
    <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" output="screen" />

</launch>
  • 1
    点赞
  • 3
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值