mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-19 18:59:06 +08:00
WIP: add X3
This commit is contained in:
parent
61226a39bd
commit
04ac07f07a
10
ROMFS/px4fmu_common/init.d-posix/airframes/4001_x3
Normal file
10
ROMFS/px4fmu_common/init.d-posix/airframes/4001_x3
Normal file
@ -0,0 +1,10 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Ignition Gazebo X3
|
||||
#
|
||||
# @type Quadrotor
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_w
|
||||
@ -78,6 +78,8 @@ px4_add_romfs_files(
|
||||
3010_quadrotor_x
|
||||
3011_hexarotor_x
|
||||
|
||||
4001_x3
|
||||
|
||||
17001_tf-g1
|
||||
17002_tf-g2
|
||||
2507_cloudship
|
||||
|
||||
63
Tools/simulation/gazebo/models/X3/meshes/propeller_ccw.dae
Normal file
63
Tools/simulation/gazebo/models/X3/meshes/propeller_ccw.dae
Normal file
File diff suppressed because one or more lines are too long
63
Tools/simulation/gazebo/models/X3/meshes/propeller_cw.dae
Normal file
63
Tools/simulation/gazebo/models/X3/meshes/propeller_cw.dae
Normal file
File diff suppressed because one or more lines are too long
10172
Tools/simulation/gazebo/models/X3/meshes/x3.dae
Normal file
10172
Tools/simulation/gazebo/models/X3/meshes/x3.dae
Normal file
File diff suppressed because one or more lines are too long
BIN
Tools/simulation/gazebo/models/X3/meshes/x3.jpg
Normal file
BIN
Tools/simulation/gazebo/models/X3/meshes/x3.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 206 KiB |
20
Tools/simulation/gazebo/models/X3/model.config
Normal file
20
Tools/simulation/gazebo/models/X3/model.config
Normal file
@ -0,0 +1,20 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<model>
|
||||
<name>x3</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.6">model.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>Carlos Aguero</name>
|
||||
<email>caguero@openrobotics.org</email>
|
||||
</author>
|
||||
|
||||
<author>
|
||||
<name>Cole Biesemeyer</name>
|
||||
<email>cole@openrobotics.org</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
</description>
|
||||
</model>
|
||||
374
Tools/simulation/gazebo/models/X3/model.sdf
Normal file
374
Tools/simulation/gazebo/models/X3/model.sdf
Normal file
@ -0,0 +1,374 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<sdf version="1.6">
|
||||
<model name="X3">
|
||||
<pose>0 0 0.053302 0 0 0</pose>
|
||||
<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.0347563</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.07</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.0977</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="base_link_inertia_collision">
|
||||
<pose frame="">0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.47 0.47 0.11</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="base_link_inertia_visual">
|
||||
<pose frame="">0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/x3.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>250</update_rate>
|
||||
</sensor>
|
||||
</link>
|
||||
<link name="rotor_0">
|
||||
<pose frame="">0.13 -0.22 0.023 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>4.17041e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>4.26041e-05</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.1</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>0.1 0.1 0.1</scale>
|
||||
<uri>meshes/propeller_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>1</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name="rotor_1">
|
||||
<pose frame="">-0.13 0.2 0.023 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>4.17041e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>4.26041e-05</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.1</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>0.1 0.1 0.1</scale>
|
||||
<uri>meshes/propeller_ccw.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<name>Gazebo/Red</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>1</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name="rotor_2">
|
||||
<pose frame="">0.13 0.22 0.023 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>4.17041e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>4.26041e-05</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.1</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>0.1 0.1 0.1</scale>
|
||||
<uri>meshes/propeller_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>1</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<link name="rotor_3">
|
||||
<pose frame="">-0.13 -0.2 0.023 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>4.17041e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>4.26041e-05</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.1</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>0.1 0.1 0.1</scale>
|
||||
<uri>meshes/propeller_cw.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<name>Gazebo/Red</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>1</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
||||
<robotNamespace>X3</robotNamespace>
|
||||
<jointName>rotor_0_joint</jointName>
|
||||
<linkName>rotor_0</linkName>
|
||||
<turningDirection>ccw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>800.0</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>0</motorNumber>
|
||||
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<motorSpeedPubTopic>motor_speed/0</motorSpeedPubTopic>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
<motorType>velocity</motorType>
|
||||
</plugin>
|
||||
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
||||
<robotNamespace>X3</robotNamespace>
|
||||
<jointName>rotor_1_joint</jointName>
|
||||
<linkName>rotor_1</linkName>
|
||||
<turningDirection>ccw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>800.0</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>1</motorNumber>
|
||||
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<motorSpeedPubTopic>motor_speed/1</motorSpeedPubTopic>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
<motorType>velocity</motorType>
|
||||
</plugin>
|
||||
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
||||
<robotNamespace>X3</robotNamespace>
|
||||
<jointName>rotor_2_joint</jointName>
|
||||
<linkName>rotor_2</linkName>
|
||||
<turningDirection>cw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>800.0</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>2</motorNumber>
|
||||
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<motorSpeedPubTopic>motor_speed/2</motorSpeedPubTopic>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
<motorType>velocity</motorType>
|
||||
</plugin>
|
||||
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
||||
<robotNamespace>X3</robotNamespace>
|
||||
<jointName>rotor_3_joint</jointName>
|
||||
<linkName>rotor_3</linkName>
|
||||
<turningDirection>cw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>800.0</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>3</motorNumber>
|
||||
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<motorSpeedPubTopic>motor_speed/3</motorSpeedPubTopic>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
<motorType>velocity</motorType>
|
||||
</plugin>
|
||||
</model>
|
||||
</sdf>
|
||||
@ -4,7 +4,6 @@
|
||||
<pose>0 0 0.121078 0 0 0</pose>
|
||||
<link name="base_link">
|
||||
<pose frame="">0 0 0 0 -0 0</pose>
|
||||
|
||||
<inertial>
|
||||
<pose frame="">0 0 0 0 -0 0</pose>
|
||||
<mass>3.42</mass>
|
||||
@ -17,7 +16,6 @@
|
||||
<izz>0.148916</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name="base_link_inertia_collision">
|
||||
<pose frame="">0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
@ -143,12 +141,10 @@
|
||||
<direction>0 0 -1</direction>
|
||||
<cast_shadows>1</cast_shadows>
|
||||
</light>
|
||||
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>400</update_rate>
|
||||
<update_rate>250</update_rate>
|
||||
<imu>
|
||||
<enable_orientation>0</enable_orientation>
|
||||
<angular_velocity>
|
||||
<x>
|
||||
<noise type="gaussian">
|
||||
@ -707,7 +703,6 @@
|
||||
<use_parent_model_frame>1</use_parent_model_frame>
|
||||
</axis>
|
||||
</joint>
|
||||
<!-- now some plugins -->
|
||||
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="ignition::gazebo::systems::MulticopterMotorModel">
|
||||
<robotNamespace>X4</robotNamespace>
|
||||
<jointName>rotor_0_joint</jointName>
|
||||
|
||||
114
Tools/simulation/gazebo/worlds/x3.sdf
Normal file
114
Tools/simulation/gazebo/worlds/x3.sdf
Normal file
@ -0,0 +1,114 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<sdf version="1.6">
|
||||
<world name="quadcopter">
|
||||
<physics name="4ms" type="ode">
|
||||
<max_step_size>0.004</max_step_size>
|
||||
<real_time_factor>1.0</real_time_factor>
|
||||
</physics>
|
||||
<plugin filename="libignition-gazebo-physics-system.so" name="ignition::gazebo::systems::Physics" />
|
||||
<plugin filename="libignition-gazebo-scene-broadcaster-system.so" name="ignition::gazebo::systems::SceneBroadcaster" />
|
||||
<plugin filename="libignition-gazebo-user-commands-system.so" name="ignition::gazebo::systems::UserCommands" />
|
||||
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors">
|
||||
<render_engine>ogre2</render_engine>
|
||||
</plugin>
|
||||
<plugin filename="libignition-gazebo-imu-system.so" name="ignition::gazebo::systems::Imu" />
|
||||
<gui fullscreen="0">
|
||||
<!-- 3D scene -->
|
||||
<plugin filename="GzScene3D" name="3D View">
|
||||
<ignition-gui>
|
||||
<title>3D View</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="string" key="state">docked</property>
|
||||
</ignition-gui>
|
||||
<engine>ogre2</engine>
|
||||
<scene>scene</scene>
|
||||
<ambient_light>0.4 0.4 0.4</ambient_light>
|
||||
<background_color>0.8 0.8 0.8</background_color>
|
||||
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
|
||||
</plugin>
|
||||
<!-- World control -->
|
||||
<plugin filename="WorldControl" name="World control">
|
||||
<ignition-gui>
|
||||
<title>World control</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="bool" key="resizable">false</property>
|
||||
<property type="double" key="height">72</property>
|
||||
<property type="double" key="width">121</property>
|
||||
<property type="double" key="z">1</property>
|
||||
<property type="string" key="state">floating</property>
|
||||
<anchors target="3D View">
|
||||
<line own="left" target="left" />
|
||||
<line own="bottom" target="bottom" />
|
||||
</anchors>
|
||||
</ignition-gui>
|
||||
<play_pause>true</play_pause>
|
||||
<step>true</step>
|
||||
<start_paused>true</start_paused>
|
||||
<service>/world/quadcopter/control</service>
|
||||
<stats_topic>/world/quadcopter/stats</stats_topic>
|
||||
</plugin>
|
||||
<!-- World statistics -->
|
||||
<plugin filename="WorldStats" name="World stats">
|
||||
<ignition-gui>
|
||||
<title>World stats</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="bool" key="resizable">false</property>
|
||||
<property type="double" key="height">110</property>
|
||||
<property type="double" key="width">290</property>
|
||||
<property type="double" key="z">1</property>
|
||||
<property type="string" key="state">floating</property>
|
||||
<anchors target="3D View">
|
||||
<line own="right" target="right" />
|
||||
<line own="bottom" target="bottom" />
|
||||
</anchors>
|
||||
</ignition-gui>
|
||||
<sim_time>true</sim_time>
|
||||
<real_time>true</real_time>
|
||||
<real_time_factor>true</real_time_factor>
|
||||
<iterations>true</iterations>
|
||||
<topic>/world/quadcopter/stats</topic>
|
||||
</plugin>
|
||||
</gui>
|
||||
<light type="directional" name="sun">
|
||||
<cast_shadows>true</cast_shadows>
|
||||
<pose>0 0 10 0 0 0</pose>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.2 0.2 0.2 1</specular>
|
||||
<attenuation>
|
||||
<range>1000</range>
|
||||
<constant>0.9</constant>
|
||||
<linear>0.01</linear>
|
||||
<quadratic>0.001</quadratic>
|
||||
</attenuation>
|
||||
<direction>-0.5 0.1 -0.9</direction>
|
||||
</light>
|
||||
<model name="ground_plane">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
</plane>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<include>
|
||||
<uri>model://X3</uri>
|
||||
</include>
|
||||
</world>
|
||||
</sdf>
|
||||
@ -1,139 +1,114 @@
|
||||
<?xml version="1.0" ?>
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<sdf version="1.6">
|
||||
<world name="quadcopter">
|
||||
<physics name="2.5 ms" type="ode">
|
||||
<max_step_size>0.002500</max_step_size>
|
||||
<real_time_factor>1.0</real_time_factor>
|
||||
</physics>
|
||||
<plugin
|
||||
filename="libignition-gazebo-physics-system.so"
|
||||
name="ignition::gazebo::systems::Physics">
|
||||
</plugin>
|
||||
<plugin
|
||||
filename="libignition-gazebo-scene-broadcaster-system.so"
|
||||
name="ignition::gazebo::systems::SceneBroadcaster">
|
||||
</plugin>
|
||||
<plugin
|
||||
filename="libignition-gazebo-user-commands-system.so"
|
||||
name="ignition::gazebo::systems::UserCommands">
|
||||
</plugin>
|
||||
<plugin
|
||||
filename="libignition-gazebo-sensors-system.so"
|
||||
name="ignition::gazebo::systems::Sensors">
|
||||
<render_engine>ogre2</render_engine>
|
||||
</plugin>
|
||||
<plugin filename="libignition-gazebo-imu-system.so"
|
||||
name="ignition::gazebo::systems::Imu">
|
||||
</plugin>
|
||||
<gui fullscreen="0">
|
||||
<!-- 3D scene -->
|
||||
<plugin filename="GzScene3D" name="3D View">
|
||||
<ignition-gui>
|
||||
<title>3D View</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="string" key="state">docked</property>
|
||||
</ignition-gui>
|
||||
|
||||
<engine>ogre2</engine>
|
||||
<scene>scene</scene>
|
||||
<ambient_light>0.4 0.4 0.4</ambient_light>
|
||||
<background_color>0.8 0.8 0.8</background_color>
|
||||
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
|
||||
<world name="quadcopter">
|
||||
<physics name="4ms" type="ode">
|
||||
<max_step_size>0.004</max_step_size>
|
||||
<real_time_factor>1.0</real_time_factor>
|
||||
</physics>
|
||||
<plugin filename="libignition-gazebo-physics-system.so" name="ignition::gazebo::systems::Physics" />
|
||||
<plugin filename="libignition-gazebo-scene-broadcaster-system.so" name="ignition::gazebo::systems::SceneBroadcaster" />
|
||||
<plugin filename="libignition-gazebo-user-commands-system.so" name="ignition::gazebo::systems::UserCommands" />
|
||||
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors">
|
||||
<render_engine>ogre2</render_engine>
|
||||
</plugin>
|
||||
|
||||
<!-- World control -->
|
||||
<plugin filename="WorldControl" name="World control">
|
||||
<ignition-gui>
|
||||
<title>World control</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="bool" key="resizable">false</property>
|
||||
<property type="double" key="height">72</property>
|
||||
<property type="double" key="width">121</property>
|
||||
<property type="double" key="z">1</property>
|
||||
|
||||
<property type="string" key="state">floating</property>
|
||||
<anchors target="3D View">
|
||||
<line own="left" target="left"/>
|
||||
<line own="bottom" target="bottom"/>
|
||||
</anchors>
|
||||
</ignition-gui>
|
||||
|
||||
<play_pause>true</play_pause>
|
||||
<step>true</step>
|
||||
<start_paused>true</start_paused>
|
||||
<service>/world/quadcopter/control</service>
|
||||
<stats_topic>/world/quadcopter/stats</stats_topic>
|
||||
|
||||
</plugin>
|
||||
|
||||
<!-- World statistics -->
|
||||
<plugin filename="WorldStats" name="World stats">
|
||||
<ignition-gui>
|
||||
<title>World stats</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="bool" key="resizable">false</property>
|
||||
<property type="double" key="height">110</property>
|
||||
<property type="double" key="width">290</property>
|
||||
<property type="double" key="z">1</property>
|
||||
|
||||
<property type="string" key="state">floating</property>
|
||||
<anchors target="3D View">
|
||||
<line own="right" target="right"/>
|
||||
<line own="bottom" target="bottom"/>
|
||||
</anchors>
|
||||
</ignition-gui>
|
||||
|
||||
<sim_time>true</sim_time>
|
||||
<real_time>true</real_time>
|
||||
<real_time_factor>true</real_time_factor>
|
||||
<iterations>true</iterations>
|
||||
<topic>/world/quadcopter/stats</topic>
|
||||
|
||||
</plugin>
|
||||
|
||||
</gui>
|
||||
|
||||
<light type="directional" name="sun">
|
||||
<cast_shadows>true</cast_shadows>
|
||||
<pose>0 0 10 0 0 0</pose>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.2 0.2 0.2 1</specular>
|
||||
<attenuation>
|
||||
<range>1000</range>
|
||||
<constant>0.9</constant>
|
||||
<linear>0.01</linear>
|
||||
<quadratic>0.001</quadratic>
|
||||
</attenuation>
|
||||
<direction>-0.5 0.1 -0.9</direction>
|
||||
</light>
|
||||
|
||||
<model name="ground_plane">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
</plane>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<include>
|
||||
<uri>model://X4</uri>
|
||||
</include>
|
||||
</world>
|
||||
<plugin filename="libignition-gazebo-imu-system.so" name="ignition::gazebo::systems::Imu" />
|
||||
<gui fullscreen="0">
|
||||
<!-- 3D scene -->
|
||||
<plugin filename="GzScene3D" name="3D View">
|
||||
<ignition-gui>
|
||||
<title>3D View</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="string" key="state">docked</property>
|
||||
</ignition-gui>
|
||||
<engine>ogre2</engine>
|
||||
<scene>scene</scene>
|
||||
<ambient_light>0.4 0.4 0.4</ambient_light>
|
||||
<background_color>0.8 0.8 0.8</background_color>
|
||||
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
|
||||
</plugin>
|
||||
<!-- World control -->
|
||||
<plugin filename="WorldControl" name="World control">
|
||||
<ignition-gui>
|
||||
<title>World control</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="bool" key="resizable">false</property>
|
||||
<property type="double" key="height">72</property>
|
||||
<property type="double" key="width">121</property>
|
||||
<property type="double" key="z">1</property>
|
||||
<property type="string" key="state">floating</property>
|
||||
<anchors target="3D View">
|
||||
<line own="left" target="left" />
|
||||
<line own="bottom" target="bottom" />
|
||||
</anchors>
|
||||
</ignition-gui>
|
||||
<play_pause>true</play_pause>
|
||||
<step>true</step>
|
||||
<start_paused>true</start_paused>
|
||||
<service>/world/quadcopter/control</service>
|
||||
<stats_topic>/world/quadcopter/stats</stats_topic>
|
||||
</plugin>
|
||||
<!-- World statistics -->
|
||||
<plugin filename="WorldStats" name="World stats">
|
||||
<ignition-gui>
|
||||
<title>World stats</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="bool" key="resizable">false</property>
|
||||
<property type="double" key="height">110</property>
|
||||
<property type="double" key="width">290</property>
|
||||
<property type="double" key="z">1</property>
|
||||
<property type="string" key="state">floating</property>
|
||||
<anchors target="3D View">
|
||||
<line own="right" target="right" />
|
||||
<line own="bottom" target="bottom" />
|
||||
</anchors>
|
||||
</ignition-gui>
|
||||
<sim_time>true</sim_time>
|
||||
<real_time>true</real_time>
|
||||
<real_time_factor>true</real_time_factor>
|
||||
<iterations>true</iterations>
|
||||
<topic>/world/quadcopter/stats</topic>
|
||||
</plugin>
|
||||
</gui>
|
||||
<light type="directional" name="sun">
|
||||
<cast_shadows>true</cast_shadows>
|
||||
<pose>0 0 10 0 0 0</pose>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.2 0.2 0.2 1</specular>
|
||||
<attenuation>
|
||||
<range>1000</range>
|
||||
<constant>0.9</constant>
|
||||
<linear>0.01</linear>
|
||||
<quadratic>0.001</quadratic>
|
||||
</attenuation>
|
||||
<direction>-0.5 0.1 -0.9</direction>
|
||||
</light>
|
||||
<model name="ground_plane">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
</plane>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<include>
|
||||
<uri>model://X4</uri>
|
||||
</include>
|
||||
</world>
|
||||
</sdf>
|
||||
|
||||
@ -398,6 +398,14 @@ endif()
|
||||
|
||||
|
||||
# Ignition Gazebo
|
||||
|
||||
add_custom_target(ignition_x3
|
||||
COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh $<TARGET_FILE:px4> none ignition x3 none ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
|
||||
WORKING_DIRECTORY ${SITL_WORKING_DIR}
|
||||
USES_TERMINAL
|
||||
DEPENDS logs_symlink
|
||||
)
|
||||
|
||||
add_custom_target(ignition_x4
|
||||
COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh $<TARGET_FILE:px4> none ignition x4 none ${PX4_SOURCE_DIR} ${PX4_BINARY_DIR}
|
||||
WORKING_DIRECTORY ${SITL_WORKING_DIR}
|
||||
|
||||
@ -44,21 +44,26 @@
|
||||
void IgnitionSimulator::ImuCallback(const ignition::msgs::IMU &imu)
|
||||
{
|
||||
// FLU -> FRD
|
||||
_px4_accel.update(hrt_absolute_time(),
|
||||
imu.linear_acceleration().x(),
|
||||
-imu.linear_acceleration().y(),
|
||||
-imu.linear_acceleration().z());
|
||||
static const auto q_FLU_to_FRD = ignition::math::Quaterniond(0, 1, 0, 0);
|
||||
|
||||
_px4_gyro.update(hrt_absolute_time(),
|
||||
imu.angular_velocity().x(),
|
||||
-imu.angular_velocity().y(),
|
||||
-imu.angular_velocity().z());
|
||||
ignition::math::Vector3d accel_b = q_FLU_to_FRD.RotateVector(ignition::math::Vector3d(
|
||||
imu.linear_acceleration().x(),
|
||||
imu.linear_acceleration().y(),
|
||||
imu.linear_acceleration().z()));
|
||||
|
||||
ignition::math::Vector3d gyro_b = q_FLU_to_FRD.RotateVector(ignition::math::Vector3d(
|
||||
imu.angular_velocity().x(),
|
||||
imu.angular_velocity().y(),
|
||||
imu.angular_velocity().z()));
|
||||
|
||||
_px4_accel.update(hrt_absolute_time(), accel_b.X(), accel_b.Y(), accel_b.Z());
|
||||
_px4_gyro.update(hrt_absolute_time(), gyro_b.X(), gyro_b.Y(), gyro_b.Z());
|
||||
}
|
||||
|
||||
void IgnitionSimulator::PoseInfoCallback(const ignition::msgs::Pose_V &pose)
|
||||
{
|
||||
for (int p = 0; p < pose.pose_size(); p++) {
|
||||
std::string vehicle_name = "X4";
|
||||
std::string vehicle_name = "X3";
|
||||
|
||||
if (pose.pose(p).name() == vehicle_name) {
|
||||
const hrt_abstime time_now_us = hrt_absolute_time();
|
||||
@ -118,8 +123,8 @@ void IgnitionSimulator::PoseInfoCallback(const ignition::msgs::Pose_V &pose)
|
||||
vehicle_local_position_s local_position_groundtruth{};
|
||||
local_position_groundtruth.timestamp_sample = hrt_absolute_time();
|
||||
|
||||
|
||||
const matrix::Vector3d position{pose_position.x(), pose_position.y(), pose_position.z()};
|
||||
// position ENU -> NED
|
||||
const matrix::Vector3d position{pose_position.y(), pose_position.x(), -pose_position.z()};
|
||||
const matrix::Vector3d velocity{(position - _position_prev) / dt};
|
||||
const matrix::Vector3d acceleration{(velocity - _velocity_prev) / dt};
|
||||
|
||||
@ -175,11 +180,11 @@ void IgnitionSimulator::run()
|
||||
ignition::transport::Node node;
|
||||
|
||||
// Subscribe to messages of other plugins.
|
||||
node.Subscribe("/world/quadcopter/model/X4/link/base_link/sensor/imu_sensor/imu", &IgnitionSimulator::ImuCallback,
|
||||
node.Subscribe("/world/quadcopter/model/X3/link/base_link/sensor/imu_sensor/imu", &IgnitionSimulator::ImuCallback,
|
||||
this);
|
||||
node.Subscribe("/world/quadcopter/pose/info", &IgnitionSimulator::PoseInfoCallback, this);
|
||||
|
||||
std::string topic = "/X4/command/motor_speed";
|
||||
std::string topic = "/X3/command/motor_speed";
|
||||
auto pub = node.Advertise<ignition::msgs::Actuators>(topic);
|
||||
|
||||
ignition::msgs::Actuators rotor_velocity_message;
|
||||
|
||||
@ -36,7 +36,11 @@ px4_add_library(vehicle_angular_velocity
|
||||
VehicleAngularVelocity.hpp
|
||||
)
|
||||
|
||||
target_compile_options(vehicle_angular_velocity PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
target_compile_options(vehicle_angular_velocity
|
||||
PRIVATE
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
#-DDEBUG_BUILD
|
||||
)
|
||||
|
||||
target_link_libraries(vehicle_angular_velocity
|
||||
PRIVATE
|
||||
|
||||
@ -112,7 +112,9 @@ bool VehicleAngularVelocity::UpdateSampleRate()
|
||||
}
|
||||
|
||||
// calculate sensor update rate
|
||||
if ((sample_rate_hz > 0) && PX4_ISFINITE(sample_rate_hz) && (publish_rate_hz > 0) && PX4_ISFINITE(publish_rate_hz)) {
|
||||
if (PX4_ISFINITE(sample_rate_hz) && (sample_rate_hz > 10) && (sample_rate_hz < 10'000)
|
||||
&& PX4_ISFINITE(publish_rate_hz) && (publish_rate_hz > 0)
|
||||
) {
|
||||
// check if sample rate error is greater than 1%
|
||||
const bool sample_rate_changed = (fabsf(sample_rate_hz - _filter_sample_rate_hz) / sample_rate_hz) > 0.01f;
|
||||
|
||||
|
||||
@ -35,5 +35,11 @@ px4_add_library(vehicle_imu
|
||||
VehicleIMU.cpp
|
||||
VehicleIMU.hpp
|
||||
)
|
||||
target_compile_options(vehicle_imu PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
target_compile_options(vehicle_imu
|
||||
PRIVATE
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
#-DDEBUG_BUILD
|
||||
)
|
||||
|
||||
target_link_libraries(vehicle_imu PRIVATE px4_work_queue sensor_calibration)
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user