Initial Attempt
This commit is contained in:
84
gazebo/launch/drone_landing.launch.py
Normal file
84
gazebo/launch/drone_landing.launch.py
Normal file
@@ -0,0 +1,84 @@
|
||||
#!/usr/bin/env python3
|
||||
"""
|
||||
Gazebo Launch File - Drone Landing Simulation
|
||||
Launches Gazebo with the world and spawns the drone.
|
||||
"""
|
||||
|
||||
import os
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription
|
||||
from launch.conditions import IfCondition
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
"""Generate the launch description."""
|
||||
|
||||
script_dir = os.path.dirname(os.path.abspath(__file__))
|
||||
gazebo_dir = os.path.dirname(script_dir)
|
||||
|
||||
world_file = os.path.join(gazebo_dir, 'worlds', 'drone_landing.sdf')
|
||||
model_path = os.path.join(gazebo_dir, 'models')
|
||||
drone_model = os.path.join(model_path, 'drone', 'model.sdf')
|
||||
|
||||
gz_resource_path = os.environ.get('GZ_SIM_RESOURCE_PATH', '')
|
||||
if model_path not in gz_resource_path:
|
||||
os.environ['GZ_SIM_RESOURCE_PATH'] = f"{model_path}:{gz_resource_path}"
|
||||
|
||||
use_sim_time = LaunchConfiguration('use_sim_time', default='true')
|
||||
headless = LaunchConfiguration('headless', default='false')
|
||||
|
||||
return LaunchDescription([
|
||||
DeclareLaunchArgument(
|
||||
'use_sim_time',
|
||||
default_value='true',
|
||||
description='Use simulation (Gazebo) clock'
|
||||
),
|
||||
DeclareLaunchArgument(
|
||||
'headless',
|
||||
default_value='false',
|
||||
description='Run Gazebo in headless mode (no GUI)'
|
||||
),
|
||||
|
||||
ExecuteProcess(
|
||||
cmd=['gz', 'sim', '-r', world_file],
|
||||
output='screen',
|
||||
additional_env={'GZ_SIM_RESOURCE_PATH': os.environ.get('GZ_SIM_RESOURCE_PATH', '')}
|
||||
),
|
||||
|
||||
ExecuteProcess(
|
||||
cmd=[
|
||||
'gz', 'service', '-s', '/world/drone_landing_world/create',
|
||||
'--reqtype', 'gz.msgs.EntityFactory',
|
||||
'--reptype', 'gz.msgs.Boolean',
|
||||
'--timeout', '5000',
|
||||
'--req', f'sdf_filename: "{drone_model}", name: "drone"'
|
||||
],
|
||||
output='screen'
|
||||
),
|
||||
|
||||
Node(
|
||||
package='ros_gz_bridge',
|
||||
executable='parameter_bridge',
|
||||
name='gz_bridge',
|
||||
arguments=[
|
||||
'/drone/cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist',
|
||||
'/model/drone/odometry@nav_msgs/msg/Odometry@gz.msgs.Odometry',
|
||||
'/drone/imu@sensor_msgs/msg/Imu@gz.msgs.IMU',
|
||||
'/clock@rosgraph_msgs/msg/Clock@gz.msgs.Clock',
|
||||
],
|
||||
parameters=[{'use_sim_time': use_sim_time}],
|
||||
output='screen'
|
||||
),
|
||||
])
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
print("This is a ROS 2 launch file. Run with:")
|
||||
print(" ros2 launch <package_name> drone_landing.launch.py")
|
||||
print("")
|
||||
print("Or use the standalone script:")
|
||||
print(" python3 gazebo_bridge.py")
|
||||
17
gazebo/models/drone/model.config
Normal file
17
gazebo/models/drone/model.config
Normal file
@@ -0,0 +1,17 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>competition_drone</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.8">model.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>Competition Framework</name>
|
||||
<email>competition@example.com</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
A simple quadrotor drone for the drone landing competition.
|
||||
Features velocity control via /drone/cmd_vel topic and
|
||||
publishes odometry for state feedback.
|
||||
</description>
|
||||
</model>
|
||||
400
gazebo/models/drone/model.sdf
Normal file
400
gazebo/models/drone/model.sdf
Normal file
@@ -0,0 +1,400 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!--
|
||||
Simple Quadrotor Drone Model for Competition
|
||||
|
||||
Features:
|
||||
- Box body with 4 rotors
|
||||
- IMU sensor
|
||||
- MulticopterMotorModel plugin for flight dynamics
|
||||
- Pose publisher for telemetry
|
||||
-->
|
||||
<sdf version="1.8">
|
||||
<model name="competition_drone">
|
||||
<pose>0 0 5 0 0 0</pose>
|
||||
|
||||
<!-- Main body -->
|
||||
<link name="base_link">
|
||||
<inertial>
|
||||
<mass>1.0</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="body_collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.3 0.3 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name="body_visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.3 0.3 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.6 0.1 0.1 1</ambient>
|
||||
<diffuse>0.8 0.2 0.2 1</diffuse>
|
||||
<specular>0.2 0.2 0.2 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Front-left arm -->
|
||||
<visual name="arm_fl">
|
||||
<pose>0.12 0.12 0 0 0 0.785</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.2 0.02 0.02</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.2 0.2 0.2 1</ambient>
|
||||
<diffuse>0.3 0.3 0.3 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Front-right arm -->
|
||||
<visual name="arm_fr">
|
||||
<pose>0.12 -0.12 0 0 0 -0.785</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.2 0.02 0.02</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.2 0.2 0.2 1</ambient>
|
||||
<diffuse>0.3 0.3 0.3 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Back-left arm -->
|
||||
<visual name="arm_bl">
|
||||
<pose>-0.12 0.12 0 0 0 -0.785</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.2 0.02 0.02</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.2 0.2 0.2 1</ambient>
|
||||
<diffuse>0.3 0.3 0.3 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Back-right arm -->
|
||||
<visual name="arm_br">
|
||||
<pose>-0.12 -0.12 0 0 0 0.785</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.2 0.02 0.02</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.2 0.2 0.2 1</ambient>
|
||||
<diffuse>0.3 0.3 0.3 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- IMU Sensor -->
|
||||
<sensor name="imu_sensor" type="imu">
|
||||
<always_on>true</always_on>
|
||||
<update_rate>100</update_rate>
|
||||
<imu>
|
||||
<angular_velocity>
|
||||
<x><noise type="gaussian"><mean>0</mean><stddev>0.01</stddev></noise></x>
|
||||
<y><noise type="gaussian"><mean>0</mean><stddev>0.01</stddev></noise></y>
|
||||
<z><noise type="gaussian"><mean>0</mean><stddev>0.01</stddev></noise></z>
|
||||
</angular_velocity>
|
||||
<linear_acceleration>
|
||||
<x><noise type="gaussian"><mean>0</mean><stddev>0.1</stddev></noise></x>
|
||||
<y><noise type="gaussian"><mean>0</mean><stddev>0.1</stddev></noise></y>
|
||||
<z><noise type="gaussian"><mean>0</mean><stddev>0.1</stddev></noise></z>
|
||||
</linear_acceleration>
|
||||
</imu>
|
||||
</sensor>
|
||||
|
||||
<!-- Downward-facing Camera -->
|
||||
<sensor name="camera" type="camera">
|
||||
<pose>0 0 -0.05 0 1.5708 0</pose>
|
||||
<always_on>true</always_on>
|
||||
<update_rate>30</update_rate>
|
||||
<camera>
|
||||
<horizontal_fov>1.047</horizontal_fov>
|
||||
<image>
|
||||
<width>320</width>
|
||||
<height>240</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.1</near>
|
||||
<far>20</far>
|
||||
</clip>
|
||||
</camera>
|
||||
<topic>/drone/camera</topic>
|
||||
</sensor>
|
||||
</link>
|
||||
|
||||
<!-- Rotor 1 (Front-Left, CCW) -->
|
||||
<link name="rotor_fl">
|
||||
<pose>0.17 0.17 0.05 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.01</mass>
|
||||
<inertia>
|
||||
<ixx>0.00001</ixx><ixy>0</ixy><ixz>0</ixz>
|
||||
<iyy>0.00001</iyy><iyz>0</iyz>
|
||||
<izz>0.00002</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name="rotor_visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.08</radius>
|
||||
<length>0.01</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.1 0.1 0.1 1</ambient>
|
||||
<diffuse>0.2 0.2 0.2 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="rotor_fl_joint" type="revolute">
|
||||
<parent>base_link</parent>
|
||||
<child>rotor_fl</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit><lower>-1e16</lower><upper>1e16</upper></limit>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<!-- Rotor 2 (Front-Right, CW) -->
|
||||
<link name="rotor_fr">
|
||||
<pose>0.17 -0.17 0.05 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.01</mass>
|
||||
<inertia>
|
||||
<ixx>0.00001</ixx><ixy>0</ixy><ixz>0</ixz>
|
||||
<iyy>0.00001</iyy><iyz>0</iyz>
|
||||
<izz>0.00002</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name="rotor_visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.08</radius>
|
||||
<length>0.01</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.1 0.1 0.1 1</ambient>
|
||||
<diffuse>0.2 0.2 0.2 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="rotor_fr_joint" type="revolute">
|
||||
<parent>base_link</parent>
|
||||
<child>rotor_fr</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit><lower>-1e16</lower><upper>1e16</upper></limit>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<!-- Rotor 3 (Back-Left, CW) -->
|
||||
<link name="rotor_bl">
|
||||
<pose>-0.17 0.17 0.05 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.01</mass>
|
||||
<inertia>
|
||||
<ixx>0.00001</ixx><ixy>0</ixy><ixz>0</ixz>
|
||||
<iyy>0.00001</iyy><iyz>0</iyz>
|
||||
<izz>0.00002</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name="rotor_visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.08</radius>
|
||||
<length>0.01</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.1 0.1 0.1 1</ambient>
|
||||
<diffuse>0.2 0.2 0.2 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="rotor_bl_joint" type="revolute">
|
||||
<parent>base_link</parent>
|
||||
<child>rotor_bl</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit><lower>-1e16</lower><upper>1e16</upper></limit>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<!-- Rotor 4 (Back-Right, CCW) -->
|
||||
<link name="rotor_br">
|
||||
<pose>-0.17 -0.17 0.05 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.01</mass>
|
||||
<inertia>
|
||||
<ixx>0.00001</ixx><ixy>0</ixy><ixz>0</ixz>
|
||||
<iyy>0.00001</iyy><iyz>0</iyz>
|
||||
<izz>0.00002</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name="rotor_visual">
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.08</radius>
|
||||
<length>0.01</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.1 0.1 0.1 1</ambient>
|
||||
<diffuse>0.2 0.2 0.2 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
<joint name="rotor_br_joint" type="revolute">
|
||||
<parent>base_link</parent>
|
||||
<child>rotor_br</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit><lower>-1e16</lower><upper>1e16</upper></limit>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<!-- MulticopterMotorModel Plugin for each rotor -->
|
||||
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
|
||||
<robotNamespace>drone</robotNamespace>
|
||||
<jointName>rotor_fl_joint</jointName>
|
||||
<linkName>rotor_fl</linkName>
|
||||
<turningDirection>ccw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>1000</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>0</motorNumber>
|
||||
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
</plugin>
|
||||
|
||||
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
|
||||
<robotNamespace>drone</robotNamespace>
|
||||
<jointName>rotor_fr_joint</jointName>
|
||||
<linkName>rotor_fr</linkName>
|
||||
<turningDirection>cw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>1000</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>1</motorNumber>
|
||||
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
</plugin>
|
||||
|
||||
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
|
||||
<robotNamespace>drone</robotNamespace>
|
||||
<jointName>rotor_bl_joint</jointName>
|
||||
<linkName>rotor_bl</linkName>
|
||||
<turningDirection>cw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>1000</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>2</motorNumber>
|
||||
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
</plugin>
|
||||
|
||||
<plugin filename="gz-sim-multicopter-motor-model-system" name="gz::sim::systems::MulticopterMotorModel">
|
||||
<robotNamespace>drone</robotNamespace>
|
||||
<jointName>rotor_br_joint</jointName>
|
||||
<linkName>rotor_br</linkName>
|
||||
<turningDirection>ccw</turningDirection>
|
||||
<timeConstantUp>0.0125</timeConstantUp>
|
||||
<timeConstantDown>0.025</timeConstantDown>
|
||||
<maxRotVelocity>1000</maxRotVelocity>
|
||||
<motorConstant>8.54858e-06</motorConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<commandSubTopic>command/motor_speed</commandSubTopic>
|
||||
<motorNumber>3</motorNumber>
|
||||
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
|
||||
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
|
||||
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
|
||||
</plugin>
|
||||
|
||||
<!-- Multicopter Velocity Controller -->
|
||||
<plugin filename="gz-sim-multicopter-control-system" name="gz::sim::systems::MulticopterVelocityControl">
|
||||
<robotNamespace>drone</robotNamespace>
|
||||
<commandSubTopic>cmd_vel</commandSubTopic>
|
||||
<enableSubTopic>enable</enableSubTopic>
|
||||
<comLinkName>base_link</comLinkName>
|
||||
<velocityGain>2.7 2.7 2.7</velocityGain>
|
||||
<attitudeGain>2 3 0.15</attitudeGain>
|
||||
<angularRateGain>0.4 0.52 0.18</angularRateGain>
|
||||
<maximumLinearAcceleration>2 2 2</maximumLinearAcceleration>
|
||||
|
||||
<rotorConfiguration>
|
||||
<rotor>
|
||||
<jointName>rotor_fl_joint</jointName>
|
||||
<forceConstant>8.54858e-06</forceConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<direction>1</direction>
|
||||
</rotor>
|
||||
<rotor>
|
||||
<jointName>rotor_fr_joint</jointName>
|
||||
<forceConstant>8.54858e-06</forceConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<direction>-1</direction>
|
||||
</rotor>
|
||||
<rotor>
|
||||
<jointName>rotor_bl_joint</jointName>
|
||||
<forceConstant>8.54858e-06</forceConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<direction>-1</direction>
|
||||
</rotor>
|
||||
<rotor>
|
||||
<jointName>rotor_br_joint</jointName>
|
||||
<forceConstant>8.54858e-06</forceConstant>
|
||||
<momentConstant>0.016</momentConstant>
|
||||
<direction>1</direction>
|
||||
</rotor>
|
||||
</rotorConfiguration>
|
||||
</plugin>
|
||||
|
||||
<!-- Odometry Publisher -->
|
||||
<plugin filename="gz-sim-odometry-publisher-system" name="gz::sim::systems::OdometryPublisher">
|
||||
<odom_frame>odom</odom_frame>
|
||||
<robot_base_frame>base_link</robot_base_frame>
|
||||
<odom_publish_frequency>50</odom_publish_frequency>
|
||||
</plugin>
|
||||
|
||||
<!-- Pose Publisher for telemetry -->
|
||||
<plugin filename="gz-sim-pose-publisher-system" name="gz::sim::systems::PosePublisher">
|
||||
<publish_link_pose>true</publish_link_pose>
|
||||
<publish_nested_model_pose>true</publish_nested_model_pose>
|
||||
<update_frequency>50</update_frequency>
|
||||
</plugin>
|
||||
|
||||
</model>
|
||||
</sdf>
|
||||
138
gazebo/worlds/drone_landing.sdf
Normal file
138
gazebo/worlds/drone_landing.sdf
Normal file
@@ -0,0 +1,138 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!--
|
||||
Drone Landing Competition - Gazebo World
|
||||
|
||||
This world contains:
|
||||
- Ground plane with grid texture
|
||||
- Landing pad (rover) at origin
|
||||
- Drone spawned at 5m altitude
|
||||
- Sun for lighting
|
||||
-->
|
||||
<sdf version="1.8">
|
||||
<world name="drone_landing_world">
|
||||
|
||||
<!-- Physics configuration -->
|
||||
<physics name="1ms" type="ignored">
|
||||
<max_step_size>0.001</max_step_size>
|
||||
<real_time_factor>1.0</real_time_factor>
|
||||
</physics>
|
||||
|
||||
<!-- Required plugins -->
|
||||
<plugin filename="gz-sim-physics-system" name="gz::sim::systems::Physics"/>
|
||||
<plugin filename="gz-sim-user-commands-system" name="gz::sim::systems::UserCommands"/>
|
||||
<plugin filename="gz-sim-scene-broadcaster-system" name="gz::sim::systems::SceneBroadcaster"/>
|
||||
<plugin filename="gz-sim-sensors-system" name="gz::sim::systems::Sensors">
|
||||
<render_engine>ogre2</render_engine>
|
||||
</plugin>
|
||||
<plugin filename="gz-sim-imu-system" name="gz::sim::systems::Imu"/>
|
||||
|
||||
<!-- Lighting -->
|
||||
<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>
|
||||
|
||||
<!-- Ground Plane -->
|
||||
<model name="ground_plane">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.3 0.3 0.3 1</ambient>
|
||||
<diffuse>0.7 0.7 0.7 1</diffuse>
|
||||
<specular>0.01 0.01 0.01 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
|
||||
<!-- Landing Pad (Rover) -->
|
||||
<model name="landing_pad">
|
||||
<static>true</static>
|
||||
<pose>0 0 0.15 0 0 0</pose>
|
||||
<link name="base_link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1.0 1.0 0.3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1.0 1.0 0.3</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.1 0.4 0.1 1</ambient>
|
||||
<diffuse>0.2 0.6 0.2 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Landing pad "H" marker -->
|
||||
<visual name="h_marker">
|
||||
<pose>0 0 0.151 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.6 0.1 0.001</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 1 1 1</ambient>
|
||||
<diffuse>1 1 1 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
<visual name="h_left">
|
||||
<pose>-0.25 0 0.151 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.1 0.6 0.001</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 1 1 1</ambient>
|
||||
<diffuse>1 1 1 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
<visual name="h_right">
|
||||
<pose>0.25 0 0.151 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.1 0.6 0.001</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 1 1 1</ambient>
|
||||
<diffuse>1 1 1 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
|
||||
</world>
|
||||
</sdf>
|
||||
Reference in New Issue
Block a user