gz models: fix deprecated warnings (#21285)

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
This commit is contained in:
Beniamino Pozzan 2023-03-13 12:28:20 -07:00 committed by GitHub
parent fd33e60f78
commit 82dce9353c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
5 changed files with 16 additions and 29 deletions

View File

@ -209,7 +209,6 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name="left_elevon">
@ -638,7 +637,6 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<joint name="RightWheelJoint" type="revolute">
@ -655,7 +653,6 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<joint name="CenterWheelJoint" type="revolute">
@ -672,7 +669,6 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<plugin filename="gz-sim-lift-drag-system" name="gz::sim::systems::LiftDrag">
@ -807,7 +803,7 @@
<sub_topic>servo_3</sub_topic>
<p_gain>10.0</p_gain>
</plugin>
<plugin filename="ignition-gazebo-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_puller_joint</jointName>
<linkName>rotor_puller</linkName>
<turningDirection>cw</turningDirection>

View File

@ -208,7 +208,6 @@
<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'>
@ -272,7 +271,6 @@
<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'>
@ -336,7 +334,6 @@
<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'>
@ -400,7 +397,6 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
@ -466,7 +462,6 @@
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>

View File

@ -302,7 +302,6 @@
<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">
@ -375,7 +374,6 @@
<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">
@ -448,7 +446,6 @@
<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">
@ -521,10 +518,9 @@
<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">
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>

View File

@ -2,7 +2,7 @@
<sdf version='1.9'>
<model name='x500-vision'>
<include merge='true'>
<uri>https://fuel.gazebosim.org/1.0/RudisLaboratories/models/x500-Base</uri>
<uri>x500</uri>
</include>
<plugin
filename="gz-sim-odometry-publisher-system"

View File

@ -5,22 +5,22 @@
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system'/>
<plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/>
<plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/>
<plugin name='ignition::gazebo::systems::Contact' filename='ignition-gazebo-contact-system'/>
<plugin name='ignition::gazebo::systems::Imu' filename='ignition-gazebo-imu-system'/>
<plugin name='ignition::gazebo::systems::AirPressure' filename='ignition-gazebo-air-pressure-system'/>
<plugin name='ignition::gazebo::systems::Sensors' filename='ignition-gazebo-sensors-system'>
<plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
<plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
<plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>
<plugin name='gz::sim::systems::Contact' filename='gz-sim-contact-system'/>
<plugin name='gz::sim::systems::Imu' filename='gz-sim-imu-system'/>
<plugin name='gz::sim::systems::AirPressure' filename='gz-sim-air-pressure-system'/>
<plugin name='gz::sim::systems::Sensors' filename='gz-sim-sensors-system'>
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen='false'>
<plugin name='3D View' filename='GzScene3D'>
<ignition-gui>
<gz-gui>
<title>3D View</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='string' key='state'>docked</property>
</ignition-gui>
</gz-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.5984631152222222 0.5984631152222222 0.5984631152222222</ambient_light>
@ -28,7 +28,7 @@
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>
<plugin name='World control' filename='WorldControl'>
<ignition-gui>
<gz-gui>
<title>World control</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
@ -40,13 +40,13 @@
<line own='left' target='left'/>
<line own='bottom' target='bottom'/>
</anchors>
</ignition-gui>
</gz-gui>
<play_pause>1</play_pause>
<step>1</step>
<start_paused>1</start_paused>
</plugin>
<plugin name='World stats' filename='WorldStats'>
<ignition-gui>
<gz-gui>
<title>World stats</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
@ -58,7 +58,7 @@
<line own='right' target='right'/>
<line own='bottom' target='bottom'/>
</anchors>
</ignition-gui>
</gz-gui>
<sim_time>1</sim_time>
<real_time>1</real_time>
<real_time_factor>1</real_time_factor>