赞
踩
1. 首先对ZD550SoliWorks文件转出stl格式文件,进行Blender软件导入,完成1000:1比例的缩小。
这里注意,对无人机的位置进行调整,让其中心在质心位置的同时,让质心在坐标轴原点0.2m高度处,保证后续对其碰撞区域设置方便。
2.通过Blender软件将上述文件导出为dae文件,进一步参考PX4官方仿真平台的iris模型,对本ZD550平台进行sdf文件编写:https://github.com/PX4/PX4-Autopilot.git
3.具体仿真出来的模型如图。
sdf文件如下:
- <sdf version='1.6'>
- <model name='Z550'>
- <link name='base_link'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <inertial>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <mass>1.5</mass>
- <inertia>
- <ixx>0.029125</ixx>
- <ixy>0</ixy>
- <ixz>0</ixz>
- <iyy>0.029125</iyy>
- <iyz>0</iyz>
- <izz>0.055225</izz>
- </inertia>
- </inertial>
- <collision name='base_link_inertia_collision_4'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <box>
- <size>0.47 0.47 0.005</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_4'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <mesh>
- <scale>1 1 1</scale>
- <uri>model://Z550/meshes/ZD550_motors_amend.dae</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 frame=''>0 0 0 0 -0 0</pose>
- <inertial>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <mass>0.015</mass>
- <inertia>
- <ixx>1e-05</ixx>
- <ixy>0</ixy>
- <ixz>0</ixz>
- <iyy>1e-05</iyy>
- <iyz>0</iyz>
- <izz>1e-05</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>0</use_parent_model_frame>
- </axis>
- </joint>
- <link name='rotor_0'>
- <pose frame=''>0.2 -0.2 0.34 0 -0 0</pose>
- <inertial>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <mass>0.005</mass>
- <inertia>
- <ixx>9.75e-07</ixx>
- <ixy>0</ixy>
- <ixz>0</ixz>
- <iyy>0.000273104</iyy>
- <iyz>0</iyz>
- <izz>0.000274004</izz>
- </inertia>
- </inertial>
- <collision name='rotor_0_collision'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <cylinder>
- <length>0.005</length>
- <radius>0.128</radius>
- </cylinder>
- </geometry>
- <surface>
- <contact>
- <ode/>
- </contact>
- <friction>
- <ode/>
- </friction>
- </surface>
- </collision>
- <visual name='rotor_0_visual'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <mesh>
- <scale>1 1 1</scale>
- <uri>model://rotors_description/meshes/iris_prop_ccw.dae</uri>
- </mesh>
- </geometry>
- <material>
- <script>
- <name>Gazebo/Blue</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>0</use_parent_model_frame>
- </axis>
- </joint>
- <link name='rotor_1'>
- <pose frame=''>-0.2 0.2 0.34 0 -0 0</pose>
- <inertial>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <mass>0.005</mass>
- <inertia>
- <ixx>9.75e-07</ixx>
- <ixy>0</ixy>
- <ixz>0</ixz>
- <iyy>0.000273104</iyy>
- <iyz>0</iyz>
- <izz>0.000274004</izz>
- </inertia>
- </inertial>
- <collision name='rotor_1_collision'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <cylinder>
- <length>0.005</length>
- <radius>0.128</radius>
- </cylinder>
- </geometry>
- <surface>
- <contact>
- <ode/>
- </contact>
- <friction>
- <ode/>
- </friction>
- </surface>
- </collision>
- <visual name='rotor_1_visual'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <mesh>
- <scale>1 1 1</scale>
- <uri>model://rotors_description/meshes/iris_prop_ccw.dae</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>
- <joint name='rotor_1_joint' type='revolute'>
- <child>rotor_1</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>0</use_parent_model_frame>
- </axis>
- </joint>
- <link name='rotor_2'>
- <pose frame=''>0.2 0.2 0.34 0 -0 0</pose>
- <inertial>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <mass>0.005</mass>
- <inertia>
- <ixx>9.75e-07</ixx>
- <ixy>0</ixy>
- <ixz>0</ixz>
- <iyy>0.000273104</iyy>
- <iyz>0</iyz>
- <izz>0.000274004</izz>
- </inertia>
- </inertial>
- <collision name='rotor_2_collision'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <cylinder>
- <length>0.005</length>
- <radius>0.128</radius>
- </cylinder>
- </geometry>
- <surface>
- <contact>
- <ode/>
- </contact>
- <friction>
- <ode/>
- </friction>
- </surface>
- </collision>
- <visual name='rotor_2_visual'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <mesh>
- <scale>1 1 1</scale>
- <uri>model://rotors_description/meshes/iris_prop_cw.dae</uri>
- </mesh>
- </geometry>
- <material>
- <script>
- <name>Gazebo/Blue</name>
- <uri>file://media/materials/scripts/gazebo.material</uri>
- </script>
- </material>
- </visual>
- <gravity>1</gravity>
- <velocity_decay/>
- </link>
- <joint name='rotor_2_joint' type='revolute'>
- <child>rotor_2</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>0</use_parent_model_frame>
- </axis>
- </joint>
- <link name='rotor_3'>
- <pose frame=''>-0.2 -0.2 0.34 0 -0 0</pose>
- <inertial>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <mass>0.005</mass>
- <inertia>
- <ixx>9.75e-07</ixx>
- <ixy>0</ixy>
- <ixz>0</ixz>
- <iyy>0.000273104</iyy>
- <iyz>0</iyz>
- <izz>0.000274004</izz>
- </inertia>
- </inertial>
- <collision name='rotor_3_collision'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <cylinder>
- <length>0.005</length>
- <radius>0.128</radius>
- </cylinder>
- </geometry>
- <surface>
- <contact>
- <ode/>
- </contact>
- <friction>
- <ode/>
- </friction>
- </surface>
- </collision>
- <visual name='rotor_3_visual'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <mesh>
- <scale>1 1 1</scale>
- <uri>model://rotors_description/meshes/iris_prop_cw.dae</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>
- <joint name='rotor_3_joint' type='revolute'>
- <child>rotor_3</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>0</use_parent_model_frame>
- </axis>
- </joint>
- <plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
- <robotNamespace/>
- <linkName>base_link</linkName>
- <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
- </plugin>
- <plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'>
- <robotNamespace/>
- <jointName>rotor_0_joint</jointName>
- <linkName>rotor_0</linkName>
- <turningDirection>ccw</turningDirection>
- <timeConstantUp>0.0125</timeConstantUp>
- <timeConstantDown>0.025</timeConstantDown>
- <maxRotVelocity>1100</maxRotVelocity>
- <motorConstant>8.54858e-06</motorConstant>
- <momentConstant>0.06</momentConstant>
- <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
- <motorNumber>0</motorNumber>
- <rotorDragCoefficient>0.000175</rotorDragCoefficient>
- <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
- <motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic>
- <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
- </plugin>
- <plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'>
- <robotNamespace/>
- <jointName>rotor_1_joint</jointName>
- <linkName>rotor_1</linkName>
- <turningDirection>ccw</turningDirection>
- <timeConstantUp>0.0125</timeConstantUp>
- <timeConstantDown>0.025</timeConstantDown>
- <maxRotVelocity>1100</maxRotVelocity>
- <motorConstant>8.54858e-06</motorConstant>
- <momentConstant>0.06</momentConstant>
- <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
- <motorNumber>1</motorNumber>
- <rotorDragCoefficient>0.000175</rotorDragCoefficient>
- <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
- <motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic>
- <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
- </plugin>
- <plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
- <robotNamespace/>
- <jointName>rotor_2_joint</jointName>
- <linkName>rotor_2</linkName>
- <turningDirection>cw</turningDirection>
- <timeConstantUp>0.0125</timeConstantUp>
- <timeConstantDown>0.025</timeConstantDown>
- <maxRotVelocity>1100</maxRotVelocity>
- <motorConstant>8.54858e-06</motorConstant>
- <momentConstant>0.06</momentConstant>
- <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
- <motorNumber>2</motorNumber>
- <rotorDragCoefficient>0.000175</rotorDragCoefficient>
- <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
- <motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic>
- <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
- </plugin>
- <plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'>
- <robotNamespace/>
- <jointName>rotor_3_joint</jointName>
- <linkName>rotor_3</linkName>
- <turningDirection>cw</turningDirection>
- <timeConstantUp>0.0125</timeConstantUp>
- <timeConstantDown>0.025</timeConstantDown>
- <maxRotVelocity>1100</maxRotVelocity>
- <motorConstant>8.54858e-06</motorConstant>
- <momentConstant>0.06</momentConstant>
- <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
- <motorNumber>3</motorNumber>
- <rotorDragCoefficient>0.000175</rotorDragCoefficient>
- <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
- <motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic>
- <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
- </plugin>
- <plugin name='gps_plugin' filename='libgazebo_gps_plugin.so'>
- <robotNamespace/>
- <gpsNoise>1</gpsNoise>
- </plugin>
- <plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'>
- <robotNamespace/>
- <pubRate>100</pubRate>
- <noiseDensity>0.0004</noiseDensity>
- <randomWalk>6.4e-06</randomWalk>
- <biasCorrelationTime>600</biasCorrelationTime>
- <magTopic>/mag</magTopic>
- </plugin>
- <plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
- <robotNamespace/>
- <pubRate>50</pubRate>
- <baroTopic>/baro</baroTopic>
- </plugin>
- <plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
- <robotNamespace/>
- <imuSubTopic>/imu</imuSubTopic>
- <gpsSubTopic>/gps</gpsSubTopic>
- <magSubTopic>/mag</magSubTopic>
- <baroSubTopic>/baro</baroSubTopic>
- <mavlink_addr>INADDR_ANY</mavlink_addr>
- <mavlink_udp_port>14560</mavlink_udp_port>
- <mavlink_tcp_port>4560</mavlink_tcp_port>
- <serialEnabled>0</serialEnabled>
- <serialDevice>/dev/ttyACM0</serialDevice>
- <baudRate>921600</baudRate>
- <qgc_addr>INADDR_ANY</qgc_addr>
- <qgc_udp_port>14550</qgc_udp_port>
- <sdk_addr>INADDR_ANY</sdk_addr>
- <sdk_udp_port>14540</sdk_udp_port>
- <hil_mode>0</hil_mode>
- <hil_state_level>0</hil_state_level>
- <vehicle_is_tailsitter>0</vehicle_is_tailsitter>
- <send_vision_estimation>1</send_vision_estimation>
- <send_odometry>0</send_odometry>
- <enable_lockstep>1</enable_lockstep>
- <use_tcp>1</use_tcp>
- <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
- <control_channels>
- <channel name='rotor1'>
- <input_index>0</input_index>
- <input_offset>0</input_offset>
- <input_scaling>1000</input_scaling>
- <zero_position_disarmed>0</zero_position_disarmed>
- <zero_position_armed>100</zero_position_armed>
- <joint_control_type>velocity</joint_control_type>
- </channel>
- <channel name='rotor2'>
- <input_index>1</input_index>
- <input_offset>0</input_offset>
- <input_scaling>1000</input_scaling>
- <zero_position_disarmed>0</zero_position_disarmed>
- <zero_position_armed>100</zero_position_armed>
- <joint_control_type>velocity</joint_control_type>
- </channel>
- <channel name='rotor3'>
- <input_index>2</input_index>
- <input_offset>0</input_offset>
- <input_scaling>1000</input_scaling>
- <zero_position_disarmed>0</zero_position_disarmed>
- <zero_position_armed>100</zero_position_armed>
- <joint_control_type>velocity</joint_control_type>
- </channel>
- <channel name='rotor4'>
- <input_index>3</input_index>
- <input_offset>0</input_offset>
- <input_scaling>1000</input_scaling>
- <zero_position_disarmed>0</zero_position_disarmed>
- <zero_position_armed>100</zero_position_armed>
- <joint_control_type>velocity</joint_control_type>
- </channel>
- <channel name='rotor5'>
- <input_index>4</input_index>
- <input_offset>1</input_offset>
- <input_scaling>324.6</input_scaling>
- <zero_position_disarmed>0</zero_position_disarmed>
- <zero_position_armed>0</zero_position_armed>
- <joint_control_type>velocity</joint_control_type>
- <joint_control_pid>
- <p>0.1</p>
- <i>0</i>
- <d>0</d>
- <iMax>0.0</iMax>
- <iMin>0.0</iMin>
- <cmdMax>2</cmdMax>
- <cmdMin>-2</cmdMin>
- </joint_control_pid>
- <joint_name>zephyr_delta_wing::propeller_joint</joint_name>
- </channel>
- <channel name='rotor6'>
- <input_index>5</input_index>
- <input_offset>0</input_offset>
- <input_scaling>0.524</input_scaling>
- <zero_position_disarmed>0</zero_position_disarmed>
- <zero_position_armed>0</zero_position_armed>
- <joint_control_type>position</joint_control_type>
- <joint_name>zephyr_delta_wing::flap_left_joint</joint_name>
- <joint_control_pid>
- <p>10.0</p>
- <i>0</i>
- <d>0</d>
- <iMax>0</iMax>
- <iMin>0</iMin>
- <cmdMax>20</cmdMax>
- <cmdMin>-20</cmdMin>
- </joint_control_pid>
- </channel>
- <channel name='rotor7'>
- <input_index>6</input_index>
- <input_offset>0</input_offset>
- <input_scaling>0.524</input_scaling>
- <zero_position_disarmed>0</zero_position_disarmed>
- <zero_position_armed>0</zero_position_armed>
- <joint_control_type>position</joint_control_type>
- <joint_name>zephyr_delta_wing::flap_right_joint</joint_name>
- <joint_control_pid>
- <p>10.0</p>
- <i>0</i>
- <d>0</d>
- <iMax>0</iMax>
- <iMin>0</iMin>
- <cmdMax>20</cmdMax>
- <cmdMin>-20</cmdMin>
- </joint_control_pid>
- </channel>
- <channel name='rotor8'>
- <input_index>7</input_index>
- <input_offset>0</input_offset>
- <input_scaling>0.524</input_scaling>
- <zero_position_disarmed>0</zero_position_disarmed>
- <zero_position_armed>0</zero_position_armed>
- <joint_control_type>position</joint_control_type>
- </channel>
- </control_channels>
- </plugin>
- <static>0</static>
- <plugin name='rotors_gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
- <robotNamespace/>
- <linkName>/imu_link</linkName>
- <imuTopic>/imu</imuTopic>
- <gyroscopeNoiseDensity>0.00018665</gyroscopeNoiseDensity>
- <gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
- <gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
- <gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
- <accelerometerNoiseDensity>0.00186</accelerometerNoiseDensity>
- <accelerometerRandomWalk>0.006</accelerometerRandomWalk>
- <accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
- <accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
- </plugin>
- </model>
- </sdf>
完成这一过程中间,本来是设计了一套桨叶的,但使用该桨叶仿真时,需要对系统的PID参数重新调整,否则起飞过程飘忽不定。
4. 通过到Mid360官网(Downloads - Mid-360 激光雷达 - Livox)下载模型文件,按照上述步骤导出dae文件,注意Mid360的坐标系。
5. 根据肖昆大佬的xtdrone文档进行Mid360的插件布置,三维固态激光SLAM(livox) · 语雀
配置好的Mid360sdf文件为:
- <sdf version='1.6'>
- <model name='Mid360'>
- <link name='livox_base'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <inertial>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <mass>0.2</mass>
- <inertia>
- <ixx>0.02</ixx>
- <ixy>0</ixy>
- <ixz>0</ixz>
- <iyy>0.02</iyy>
- <iyz>0</iyz>
- <izz>0.02</izz>
- </inertia>
- </inertial>
- <collision name='livox_base_collision'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <mesh>
- <scale>1 1 1</scale>
- <uri>model://livox_mid40/meshes/livox_mid40.dae</uri>
- </mesh>
- </geometry>
- </collision>
- <visual name='livox_base_visual'>
- <pose frame=''>0 0 0 0 -0 0</pose>
- <geometry>
- <mesh>
- <scale>1 1 1</scale>
- <uri>model://livox_mid40/meshes/mid360_rules.dae</uri>
- </mesh>
- </geometry>
- </visual>
- <gravity>1</gravity>
- <velocity_decay/>
- <sensor name='laser_livox' type='ray'>
- <visualize>1</visualize>
- <update_rate>10</update_rate>
- <always_on>1</always_on>
- <plugin name='gazebo_ros_laser_controller' filename='liblivox_laser_simulation.so'>
- <ray>
- <scan>
- <horizontal>
- <samples>100</samples>
- <resolution>1</resolution>
- <min_angle>-0.614355377778</min_angle>
- <max_angle>0.614355377778</max_angle>
- </horizontal>
- <vertical>
- <samples>50</samples>
- <resolution>1</resolution>
- <min_angle>-0.673696522222</min_angle>
- <max_angle>0.673696522222</max_angle>
- </vertical>
- </scan>
- <range>
- <min>0.1</min>
- <max>200.0</max>
- <resolution>0.002</resolution>
- </range>
- <noise>
- <type>gaussian</type>
- <mean>0.0</mean>
- <stddev>0.01</stddev>
- </noise>
- </ray>
- <visualize>1</visualize>
- <samples>10000</samples>
- <downsample>1</downsample>
- <csv_file_name>/home/ywb/PX4_Files/PX4_Firmware/Tools/sitl_gazebo/models/livox_mid40/scan_mode/mid360.csv</csv_file_name>
- <ros_topic>/scan</ros_topic>
- </plugin>
- <pose frame=''>0 0 0 0 -0 0</pose>
- </sensor>
- </link>
- </model>
- </sdf>
(1)刚开始打算按照XTdrone给出的Livox文件进行修改,将自己的dae文件放置进去,将碰撞模型和可视化模型均改为mid360.dae,仿真发现会出现卡顿的情况,目前还没有解决。暂时是使用了文档中提到的livox_mid40.dae作为碰撞参考,可视化部分还是使用mid360.dae文件。
(2)当时启动gazebo,仿真的mid360模型文件存在,但并没有点云数据,通过查看终端,发现是 mid360插件不能找到mid360.csv文件,然后最后通过写入绝对路径的方法成功仿真出点云数据,这里将PX4官方提供的velodyne的点云和mid360仿真的点云做了个大致对比,整体效果还行。
Velodyne:
Mid360:
6. 最后将Mid360固定到ZD550平台上,最后的ZD550_Mid360平台sdf文件:
- <?xml version="1.0"?>
- <sdf version="1.6">
- <model name="Z550_Mid360_down">
- <include>
- <uri>model://Z550</uri>
- </include>
- <include>
- <uri>model://Mid360</uri>
- <pose>0 0 0.155 3.1415926 0 0</pose>
- </include>
- <joint name="3Dlidar_joint" type="revolute">
- <child>Mid360::livox_base</child>
- <parent>Z550::base_link</parent>
- <axis>
- <xyz>0 0 1</xyz>
- <limit>
- <upper>0</upper>
- <lower>0</lower>
- </limit>
- </axis>
- </joint>
- </model>
- </sdf>
最终的仿真效果如下
上述文件地址:https://download.csdn.net/download/weixin_52814031/88541781?spm=1001.2014.3001.5503
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。