Added Config.py
This commit is contained in:
@@ -16,46 +16,62 @@ import numpy as np
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
# Load configuration
|
||||
try:
|
||||
from config import DRONE, ROVER, CAMERA, PHYSICS, NETWORK
|
||||
CONFIG_LOADED = True
|
||||
except ImportError:
|
||||
CONFIG_LOADED = False
|
||||
DRONE = {"mass": 1.0, "size": (0.3, 0.3, 0.1), "color": (0.8, 0.1, 0.1, 1.0),
|
||||
"start_position": (0.0, 0.0, 5.0), "thrust_scale": 15.0,
|
||||
"pitch_torque_scale": 2.0, "roll_torque_scale": 2.0, "yaw_torque_scale": 1.0}
|
||||
ROVER = {"size": (1.0, 1.0, 0.3), "color": (0.2, 0.6, 0.2, 1.0),
|
||||
"start_position": (0.0, 0.0, 0.15)}
|
||||
CAMERA = {"width": 320, "height": 240, "fov": 60.0, "near_clip": 0.1, "far_clip": 20.0}
|
||||
PHYSICS = {"gravity": -9.81, "timestep": 1/240, "telemetry_rate": 24}
|
||||
NETWORK = {"host": "0.0.0.0", "command_port": 5555, "telemetry_port": 5556}
|
||||
|
||||
|
||||
class DroneSimulator:
|
||||
"""PyBullet-based drone simulation with camera."""
|
||||
|
||||
UDP_HOST = '0.0.0.0'
|
||||
UDP_PORT = 5555
|
||||
UDP_BUFFER_SIZE = 65535
|
||||
SOCKET_TIMEOUT = 0.001
|
||||
TELEMETRY_PORT = 5556
|
||||
|
||||
PHYSICS_TIMESTEP = 1.0 / 240.0
|
||||
GRAVITY = -9.81
|
||||
TELEMETRY_INTERVAL = 10
|
||||
|
||||
DRONE_MASS = 1.0
|
||||
DRONE_SIZE = (0.3, 0.3, 0.1)
|
||||
DRONE_START_POS = (0.0, 0.0, 5.0)
|
||||
|
||||
THRUST_SCALE = 15.0
|
||||
PITCH_TORQUE_SCALE = 2.0
|
||||
ROLL_TORQUE_SCALE = 2.0
|
||||
YAW_TORQUE_SCALE = 1.0
|
||||
HOVER_THRUST = DRONE_MASS * abs(GRAVITY)
|
||||
|
||||
ROVER_SIZE = (1.0, 1.0, 0.3)
|
||||
ROVER_POS = (0.0, 0.0, 0.15)
|
||||
|
||||
# Camera parameters
|
||||
CAMERA_WIDTH = 320
|
||||
CAMERA_HEIGHT = 240
|
||||
CAMERA_FOV = 60.0
|
||||
CAMERA_NEAR = 0.1
|
||||
CAMERA_FAR = 20.0
|
||||
CAMERA_INTERVAL = 5 # Capture every N telemetry frames
|
||||
|
||||
def __init__(self):
|
||||
print("=" * 60)
|
||||
print("Drone Simulation Host (GPS-Denied + Camera)")
|
||||
if CONFIG_LOADED:
|
||||
print(" Configuration loaded from config.py")
|
||||
print("=" * 60)
|
||||
|
||||
# Load from config
|
||||
self._udp_host = NETWORK.get("host", "0.0.0.0")
|
||||
self._udp_port = NETWORK.get("command_port", 5555)
|
||||
self._telemetry_port = NETWORK.get("telemetry_port", 5556)
|
||||
|
||||
self._gravity = PHYSICS.get("gravity", -9.81)
|
||||
self._timestep = PHYSICS.get("timestep", 1/240)
|
||||
self._telemetry_interval = int(240 / PHYSICS.get("telemetry_rate", 24))
|
||||
|
||||
self._drone_mass = DRONE.get("mass", 1.0)
|
||||
self._drone_size = DRONE.get("size", (0.3, 0.3, 0.1))
|
||||
self._drone_start = DRONE.get("start_position", (0.0, 0.0, 5.0))
|
||||
self._drone_color = DRONE.get("color", (0.8, 0.1, 0.1, 1.0))
|
||||
self._thrust_scale = DRONE.get("thrust_scale", 15.0)
|
||||
self._pitch_torque_scale = DRONE.get("pitch_torque_scale", 2.0)
|
||||
self._roll_torque_scale = DRONE.get("roll_torque_scale", 2.0)
|
||||
self._yaw_torque_scale = DRONE.get("yaw_torque_scale", 1.0)
|
||||
self._hover_thrust = self._drone_mass * abs(self._gravity)
|
||||
|
||||
self._rover_size = ROVER.get("size", (1.0, 1.0, 0.3))
|
||||
self._rover_start = list(ROVER.get("start_position", (0.0, 0.0, 0.15)))
|
||||
self._rover_color = ROVER.get("color", (0.2, 0.6, 0.2, 1.0))
|
||||
|
||||
self._camera_width = CAMERA.get("width", 320)
|
||||
self._camera_height = CAMERA.get("height", 240)
|
||||
self._camera_fov = CAMERA.get("fov", 60.0)
|
||||
self._camera_near = CAMERA.get("near_clip", 0.1)
|
||||
self._camera_far = CAMERA.get("far_clip", 20.0)
|
||||
self._camera_interval = 5
|
||||
|
||||
self._running = True
|
||||
self._step_count = 0
|
||||
self._camera_frame_count = 0
|
||||
@@ -63,7 +79,7 @@ class DroneSimulator:
|
||||
'thrust': 0.0, 'pitch': 0.0, 'roll': 0.0, 'yaw': 0.0
|
||||
}
|
||||
|
||||
self._rover_pos = list(self.ROVER_POS)
|
||||
self._rover_pos = list(self._rover_start)
|
||||
self._last_camera_image = None
|
||||
|
||||
self._init_physics()
|
||||
@@ -72,15 +88,15 @@ class DroneSimulator:
|
||||
|
||||
print("Simulation Ready! (GPS-Denied Mode)")
|
||||
print(" Sensors: IMU, Altimeter, Camera")
|
||||
print(f" Camera: {self.CAMERA_WIDTH}x{self.CAMERA_HEIGHT} @ {self.CAMERA_FOV}° FOV")
|
||||
print(f" Listening on UDP port {self.UDP_PORT}")
|
||||
print(f" Camera: {self._camera_width}x{self._camera_height} @ {self._camera_fov}° FOV")
|
||||
print(f" Listening on UDP port {self._udp_port}")
|
||||
print("=" * 60)
|
||||
|
||||
def _init_physics(self) -> None:
|
||||
print("Initializing PyBullet physics engine...")
|
||||
self._physics_client = p.connect(p.GUI)
|
||||
p.setGravity(0, 0, self.GRAVITY)
|
||||
p.setTimeStep(self.PHYSICS_TIMESTEP)
|
||||
p.setGravity(0, 0, self._gravity)
|
||||
p.setTimeStep(self._timestep)
|
||||
p.resetDebugVisualizerCamera(
|
||||
cameraDistance=8.0,
|
||||
cameraYaw=45,
|
||||
@@ -98,47 +114,47 @@ class DroneSimulator:
|
||||
|
||||
rover_collision = p.createCollisionShape(
|
||||
p.GEOM_BOX,
|
||||
halfExtents=[s/2 for s in self.ROVER_SIZE]
|
||||
halfExtents=[s/2 for s in self._rover_size]
|
||||
)
|
||||
rover_visual = p.createVisualShape(
|
||||
p.GEOM_BOX,
|
||||
halfExtents=[s/2 for s in self.ROVER_SIZE],
|
||||
rgbaColor=[0.2, 0.6, 0.2, 1.0]
|
||||
halfExtents=[s/2 for s in self._rover_size],
|
||||
rgbaColor=list(self._rover_color)
|
||||
)
|
||||
self._rover_id = p.createMultiBody(
|
||||
baseMass=0,
|
||||
baseCollisionShapeIndex=rover_collision,
|
||||
baseVisualShapeIndex=rover_visual,
|
||||
basePosition=self.ROVER_POS
|
||||
basePosition=self._rover_start
|
||||
)
|
||||
print(f" Rover created at position {self.ROVER_POS}")
|
||||
print(f" Rover created at position {self._rover_start}")
|
||||
|
||||
self._create_landing_pad_marker()
|
||||
|
||||
drone_collision = p.createCollisionShape(
|
||||
p.GEOM_BOX,
|
||||
halfExtents=[s/2 for s in self.DRONE_SIZE]
|
||||
halfExtents=[s/2 for s in self._drone_size]
|
||||
)
|
||||
drone_visual = p.createVisualShape(
|
||||
p.GEOM_BOX,
|
||||
halfExtents=[s/2 for s in self.DRONE_SIZE],
|
||||
rgbaColor=[0.8, 0.2, 0.2, 1.0]
|
||||
halfExtents=[s/2 for s in self._drone_size],
|
||||
rgbaColor=list(self._drone_color)
|
||||
)
|
||||
self._drone_id = p.createMultiBody(
|
||||
baseMass=self.DRONE_MASS,
|
||||
baseMass=self._drone_mass,
|
||||
baseCollisionShapeIndex=drone_collision,
|
||||
baseVisualShapeIndex=drone_visual,
|
||||
basePosition=self.DRONE_START_POS
|
||||
basePosition=self._drone_start
|
||||
)
|
||||
p.changeDynamics(
|
||||
self._drone_id, -1,
|
||||
linearDamping=0.1,
|
||||
angularDamping=0.5
|
||||
)
|
||||
print(f" Drone created at position {self.DRONE_START_POS}")
|
||||
print(f" Drone created at position {self._drone_start}")
|
||||
|
||||
def _create_landing_pad_marker(self) -> None:
|
||||
marker_height = self.ROVER_POS[2] + self.ROVER_SIZE[2] / 2 + 0.01
|
||||
marker_height = self._rover_start[2] + self._rover_size[2] / 2 + 0.01
|
||||
h_size = 0.3
|
||||
line_color = [1, 1, 1]
|
||||
line_width = 3
|
||||
@@ -166,10 +182,10 @@ class DroneSimulator:
|
||||
print("Initializing network...")
|
||||
self._socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
|
||||
self._socket.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
|
||||
self._socket.settimeout(self.SOCKET_TIMEOUT)
|
||||
self._socket.bind((self.UDP_HOST, self.UDP_PORT))
|
||||
self._socket.settimeout(0.001)
|
||||
self._socket.bind((self._udp_host, self._udp_port))
|
||||
self._controller_addr: Optional[Tuple[str, int]] = None
|
||||
print(f" UDP socket bound to {self.UDP_HOST}:{self.UDP_PORT}")
|
||||
print(f" UDP socket bound to {self._udp_host}:{self._udp_port}")
|
||||
|
||||
def run(self) -> None:
|
||||
print("\nStarting simulation loop...")
|
||||
@@ -188,11 +204,11 @@ class DroneSimulator:
|
||||
p.stepSimulation()
|
||||
self._step_count += 1
|
||||
|
||||
if self._step_count % self.TELEMETRY_INTERVAL == 0:
|
||||
if self._step_count % self._telemetry_interval == 0:
|
||||
self._send_telemetry()
|
||||
|
||||
elapsed = time.time() - loop_start
|
||||
sleep_time = self.PHYSICS_TIMESTEP - elapsed
|
||||
sleep_time = self._timestep - elapsed
|
||||
if sleep_time > 0:
|
||||
time.sleep(sleep_time)
|
||||
|
||||
@@ -203,8 +219,8 @@ class DroneSimulator:
|
||||
|
||||
def _receive_commands(self) -> None:
|
||||
try:
|
||||
data, addr = self._socket.recvfrom(self.UDP_BUFFER_SIZE)
|
||||
self._controller_addr = (addr[0], self.TELEMETRY_PORT)
|
||||
data, addr = self._socket.recvfrom(65535)
|
||||
self._controller_addr = (addr[0], self._telemetry_port)
|
||||
|
||||
try:
|
||||
command = json.loads(data.decode('utf-8'))
|
||||
@@ -244,7 +260,7 @@ class DroneSimulator:
|
||||
local_up = [rot_matrix[2], rot_matrix[5], rot_matrix[8]]
|
||||
|
||||
thrust_command = self._last_command['thrust']
|
||||
total_thrust = self.HOVER_THRUST + (thrust_command * self.THRUST_SCALE)
|
||||
total_thrust = self._hover_thrust + (thrust_command * self._thrust_scale)
|
||||
total_thrust = max(0, total_thrust)
|
||||
|
||||
thrust_force = [
|
||||
@@ -260,9 +276,9 @@ class DroneSimulator:
|
||||
flags=p.WORLD_FRAME
|
||||
)
|
||||
|
||||
pitch_torque = self._last_command['pitch'] * self.PITCH_TORQUE_SCALE
|
||||
roll_torque = self._last_command['roll'] * self.ROLL_TORQUE_SCALE
|
||||
yaw_torque = self._last_command['yaw'] * self.YAW_TORQUE_SCALE
|
||||
pitch_torque = self._last_command['pitch'] * self._pitch_torque_scale
|
||||
roll_torque = self._last_command['roll'] * self._roll_torque_scale
|
||||
yaw_torque = self._last_command['yaw'] * self._yaw_torque_scale
|
||||
|
||||
p.applyExternalTorque(
|
||||
self._drone_id, -1,
|
||||
@@ -283,24 +299,24 @@ class DroneSimulator:
|
||||
cameraUpVector=[math.cos(euler[2]), math.sin(euler[2]), 0]
|
||||
)
|
||||
|
||||
aspect = self.CAMERA_WIDTH / self.CAMERA_HEIGHT
|
||||
aspect = self._camera_width / self._camera_height
|
||||
projection_matrix = p.computeProjectionMatrixFOV(
|
||||
fov=self.CAMERA_FOV,
|
||||
fov=self._camera_fov,
|
||||
aspect=aspect,
|
||||
nearVal=self.CAMERA_NEAR,
|
||||
farVal=self.CAMERA_FAR
|
||||
nearVal=self._camera_near,
|
||||
farVal=self._camera_far
|
||||
)
|
||||
|
||||
_, _, rgb, _, _ = p.getCameraImage(
|
||||
width=self.CAMERA_WIDTH,
|
||||
height=self.CAMERA_HEIGHT,
|
||||
width=self._camera_width,
|
||||
height=self._camera_height,
|
||||
viewMatrix=view_matrix,
|
||||
projectionMatrix=projection_matrix,
|
||||
renderer=p.ER_BULLET_HARDWARE_OPENGL
|
||||
)
|
||||
|
||||
image = np.array(rgb, dtype=np.uint8).reshape(
|
||||
self.CAMERA_HEIGHT, self.CAMERA_WIDTH, 4
|
||||
self._camera_height, self._camera_width, 4
|
||||
)[:, :, :3]
|
||||
|
||||
# Encode as base64 for transmission
|
||||
@@ -330,7 +346,7 @@ class DroneSimulator:
|
||||
if vertical_dist <= 0 or vertical_dist > 10.0:
|
||||
return None
|
||||
|
||||
fov_rad = math.radians(self.CAMERA_FOV / 2)
|
||||
fov_rad = math.radians(self._camera_fov / 2)
|
||||
max_horizontal = vertical_dist * math.tan(fov_rad)
|
||||
|
||||
if horizontal_dist > max_horizontal:
|
||||
@@ -369,7 +385,7 @@ class DroneSimulator:
|
||||
self._camera_frame_count += 1
|
||||
camera_image = None
|
||||
|
||||
if self._camera_frame_count >= self.CAMERA_INTERVAL:
|
||||
if self._camera_frame_count >= self._camera_interval:
|
||||
self._camera_frame_count = 0
|
||||
camera_image = self._capture_camera_image()
|
||||
|
||||
@@ -388,7 +404,7 @@ class DroneSimulator:
|
||||
"linear_acceleration": {
|
||||
"x": 0.0,
|
||||
"y": 0.0,
|
||||
"z": round(-self.GRAVITY, 4)
|
||||
"z": round(-self._gravity, 4)
|
||||
}
|
||||
},
|
||||
"altimeter": {
|
||||
@@ -402,13 +418,13 @@ class DroneSimulator:
|
||||
},
|
||||
"landing_pad": pad_detection,
|
||||
"camera": {
|
||||
"width": self.CAMERA_WIDTH,
|
||||
"height": self.CAMERA_HEIGHT,
|
||||
"fov": self.CAMERA_FOV,
|
||||
"width": self._camera_width,
|
||||
"height": self._camera_height,
|
||||
"fov": self._camera_fov,
|
||||
"image": camera_image # Base64 encoded JPEG (or None)
|
||||
},
|
||||
"landed": landed_on_rover,
|
||||
"timestamp": round(self._step_count * self.PHYSICS_TIMESTEP, 4)
|
||||
"timestamp": round(self._step_count * self._timestep, 4)
|
||||
}
|
||||
|
||||
try:
|
||||
|
||||
Reference in New Issue
Block a user