【PX4二次开发】PX4添加无人机模型和一些问题的总结

从SolidWorks中导出STL模型文件

SolidWorks建模

在Solidworks中开展建模工作,搭建无人机的模型。模型主要由机体,电机,螺旋桨等零件组成。
在这里插入图片描述

SolidWorks零件添加质量属性

为了尽量与实物的质量分布相同,我在对每个零件建模的时候都提前对实物的质量和尺寸进行测量,最后自定义材料属性并赋值给零件。这样可以尽可能地保证模型和实物的相似度,最终装配体的质量属性如下:
在这里插入图片描述

新建参考坐标系并导出STL文件

此处,我选取了无人机模型的重心作为坐标系的原点,并将坐标轴的X轴对齐无人机的机头方向。
在这里插入图片描述
另存为STL,选项中选择输出坐标系为刚才新建的坐标系。

在这里插入图片描述

PX4固件中的设置

方便起见,本次直接在PX4的默认启动模型iris基础上进行更改如下(也可以参考PX4官方文档教程新定义机型,本次不涉及):

SDF文件修改

在PX4-Autopilot/Tools/sitl_gazebo/models/iris文件夹中,新建一个sdf文件。仿照iris.sdf文件修改添加无人机质量,惯性矩,电机位置,机体和螺旋桨可视化文件,电机插件(电机常数、扭力系数,最大转速等参数可以通过动力系统实验测得数据),示例如下:

microfly.sdf

<!-- DO NOT EDIT: Generated from iris.sdf.jinja -->
<sdf version='1.6'>
  <model name='microfly'>
    <link name='base_link'>
      <pose>0 0 0 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.279</mass>
        <inertia>
          <ixx>0.000509927</ixx>
          <ixy>-0.0000</ixy>
          <ixz>-0.0000</ixz>
          <iyy>0.000543117</iyy>
          <izy>-0.0000</izy>
          <izz>0.000833593</izz>
        </inertia>
      </inertial>
      <collision name='base_link_inertia_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <box>
            <size>0.136 0.096 0.069</size>
          </box>
        </geometry>
        <surface>
          <contact>
            <ode>
              <min_depth>0.001</min_depth>
              <max_vel>0</max_vel>
            </ode>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='base_link_inertia_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.001 0.001 0.001</scale>
            <uri>model://iris/meshes/microfly.STL</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <link name='/imu_link'>
      <pose>0 0 0 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.001</mass>
        <inertia>
          <ixx>1e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1e-06</iyy>
          <iyz>0</iyz>
          <izz>1e-06</izz>
        </inertia>
      </inertial>
    </link>
    <joint name='/imu_joint' type='revolute'>
      <child>/imu_link</child>
      <parent>base_link</parent>
      <axis>
        <xyz>1 0 0</xyz>
        <limit>
          <lower>0</lower>
          <upper>0</upper>
          <effort>0</effort>
          <velocity>0</velocity>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <link name='rotor_0'>
      <pose>0.0535 -0.0535 -0.0224 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.0037</mass>
        <inertia>
          <ixx>9.50e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>9.50e-07</iyy>
          <iyz>0</iyz>
          <izz>1.816e-06</izz>
        </inertia>
      </inertial>
      <collision name='rotor_0_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.045</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_0_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>0.001 0.001 0.001</scale>
            <uri>model://iris/meshes/microfly_3.5_prpo_ccw.stl</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/RedTransparent</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_0_joint' type='revolute'>
      <child>rotor_0</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <link name='rotor_1'>
      <pose>-0.0535 0.0535 -0.0224 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.0037</mass>
        <inertia>
          <ixx>9.50e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>9.50e-07</iyy>
          <iyz>0</iyz>
          <izz>1.816e-06</izz>
        </inertia>
      </inertial>
      <collision name='rotor_1_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.045</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_1_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <s
### 如何在PX4 GAZEBO仿真中为无人机模型添加相机传感器 为了在PX4 Gazebo仿真环境中成功为无人机模型添加相机传感器,需遵循特定的配置流程。此过程涉及修改SDF文件来引入新的传感器组件。 #### 修改无人机模型的SDF文件 通常情况下,在Gazebo中定义新传感器意味着编辑描述飞行器物理特性的SDF (Simulation Description Format) 文件。对于希望加入视觉能力的情况,则是在该文件内指定<sensor>标签并设置其属性以匹配所需的摄像机参数[^1]。 ```xml <!-- 插入到model.sdf --> <plugin name="camera_plugin" filename="libgazebo_ros_camera.so"> <alwaysOn>true</alwaysOn> <updateRate>30.0</updateRate> <cameraName>front_cam</cameraName> <imageTopicName>/drone/front/image_raw</imageTopicName> <cameraInfoTopicName>/drone/front/camera_info</cameraInfoTopicName> <frameName>front_cam_link</frameName> <hackBaseline>0.07</hackBaseline> <distortionK1>0.0</distortionK1> <distortionK2>0.0</distortionK2> <distortionK3>0.0</distortionK3> <distortionT1>0.0</distortionT1> <distortionT2>0.0</distortionT2> </plugin> <link name='front_cam'> <!-- 定义link的位置其他特性 --> </link> ``` 上述XML片段展示了如何向现有的无人机模型添加一个名为`front_cam`的新摄像设备,并指定了图像数据发布的主题路径以及关联的信息元数据发布地址。同时设置了帧名称用于ROS节点间通信时识别消息源。 #### 更新launch文件调用自定义模型 完成硬件描述之后,还需调整启动脚本以便加载含有新增加部件后的版本。这一步骤可能涉及到创建或更改`.world`世界场景文件中的引用对象,也可能是直接改动原有的`.launch`发射文件,确保能够正确实例化带有改进过的视觉系统的虚拟机体[^4]。 例如: ```xml <include file="$(find px4)/launch/multi_uav_mavros_sitl.launch"> <arg name="flock_name" value="my_drone"/> <arg name="vehicle_count" value="1"/> <arg name="sdf" value="$(find my_package)/models/my_custom_quadrotor/model.sdf"/> </include> ``` 这里假设已经有一个包含了定制化内容的SDF文档存放在个人工作空间内的某个包里;通过传递`sdf`参数给multi_uav_mavros_sitl.launch,可以让系统知道要使用哪一个具体的机型设计来进行模拟实验。
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值