Files
RDC_Simulation/standalone_simulation.py
2026-01-02 07:07:51 +00:00

387 lines
14 KiB
Python

#!/usr/bin/env python3
"""
Standalone Drone Simulation - Runs without ROS 2.
Includes built-in controller for landing demonstration.
Usage: python standalone_simulation.py [--pattern PATTERN] [--speed SPEED]
"""
import argparse
import base64
import json
import math
import time
from typing import Dict, Any, Optional, Tuple
import numpy as np
import pybullet as p
import pybullet_data
# Load configuration
try:
from config import DRONE, ROVER, CAMERA, PHYSICS, CONTROLLER, LANDING
CONFIG_LOADED = True
except ImportError:
CONFIG_LOADED = False
# Defaults if config.py is missing
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), "default_pattern": "stationary",
"default_speed": 0.5, "default_amplitude": 2.0}
CAMERA = {"fov": 60.0}
PHYSICS = {"gravity": -9.81, "timestep": 1/240}
CONTROLLER = {"Kp_z": 0.5, "Kd_z": 0.3, "Kp_xy": 0.3, "Kd_xy": 0.2}
LANDING = {"success_velocity": 0.5}
class StandaloneSimulation:
"""Complete simulation with built-in controller - no ROS 2 needed."""
def __init__(self, rover_pattern=None, rover_speed=None, rover_amplitude=None):
print("=" * 60)
print("Standalone Drone Simulation (No ROS 2 Required)")
if CONFIG_LOADED:
print(" Configuration loaded from config.py")
print("=" * 60)
self._running = True
self._step_count = 0
self._time = 0.0
# Use config values or arguments
self._rover_pattern = rover_pattern or ROVER.get("default_pattern", "stationary")
self._rover_speed = rover_speed if rover_speed is not None else ROVER.get("default_speed", 0.5)
self._rover_amplitude = rover_amplitude if rover_amplitude is not None else ROVER.get("default_amplitude", 2.0)
self._rover_pos = list(ROVER.get("start_position", (0.0, 0.0, 0.15)))
# Physics constants from config
self._gravity = PHYSICS.get("gravity", -9.81)
self._timestep = PHYSICS.get("timestep", 1/240)
self._control_interval = 5
# Drone constants from config
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)
# Rover constants from config
self._rover_size = ROVER.get("size", (1.0, 1.0, 0.3))
self._rover_color = ROVER.get("color", (0.2, 0.6, 0.2, 1.0))
# Camera
self._camera_fov = CAMERA.get("fov", 60.0)
# Controller gains
self._Kp_z = CONTROLLER.get("Kp_z", 0.5)
self._Kd_z = CONTROLLER.get("Kd_z", 0.3)
self._Kp_xy = CONTROLLER.get("Kp_xy", 0.3)
self._Kd_xy = CONTROLLER.get("Kd_xy", 0.2)
# Landing
self._landing_velocity = LANDING.get("success_velocity", 0.5)
# Control command
self._command = {'thrust': 0.0, 'pitch': 0.0, 'roll': 0.0, 'yaw': 0.0}
self._init_physics()
self._init_objects()
print(f" Drone Start: {self._drone_start}")
print(f" Rover Start: {self._rover_pos}")
print(f" Rover Pattern: {self._rover_pattern}")
print(f" Rover Speed: {self._rover_speed} m/s")
print(" Press Ctrl+C to exit")
print("=" * 60)
def _init_physics(self) -> None:
self._physics_client = p.connect(p.GUI)
p.setGravity(0, 0, self._gravity)
p.setTimeStep(self._timestep)
p.resetDebugVisualizerCamera(
cameraDistance=8.0,
cameraYaw=45,
cameraPitch=-30,
cameraTargetPosition=[0, 0, 1]
)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
def _init_objects(self) -> None:
self._ground_id = p.loadURDF("plane.urdf")
# Create rover (landing pad)
rover_collision = p.createCollisionShape(
p.GEOM_BOX,
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=list(self._rover_color)
)
self._rover_id = p.createMultiBody(
baseMass=0,
baseCollisionShapeIndex=rover_collision,
baseVisualShapeIndex=rover_visual,
basePosition=self._rover_pos
)
# Create landing pad marker
self._create_landing_marker()
# Create drone
drone_collision = p.createCollisionShape(
p.GEOM_BOX,
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=list(self._drone_color)
)
self._drone_id = p.createMultiBody(
baseMass=self._drone_mass,
baseCollisionShapeIndex=drone_collision,
baseVisualShapeIndex=drone_visual,
basePosition=self._drone_start
)
p.changeDynamics(
self._drone_id, -1,
linearDamping=0.1,
angularDamping=0.5
)
def _create_landing_marker(self) -> None:
marker_height = self._rover_pos[2] + self._rover_size[2] / 2 + 0.01
h_size = 0.3
line_color = [1, 1, 1]
p.addUserDebugLine([-h_size, 0, marker_height], [h_size, 0, marker_height],
lineColorRGB=line_color, lineWidth=3)
p.addUserDebugLine([-h_size, -h_size, marker_height], [-h_size, h_size, marker_height],
lineColorRGB=line_color, lineWidth=3)
p.addUserDebugLine([h_size, -h_size, marker_height], [h_size, h_size, marker_height],
lineColorRGB=line_color, lineWidth=3)
def run(self) -> None:
print("\nSimulation running...")
try:
while self._running:
loop_start = time.time()
if not p.isConnected():
break
# Update rover position
self._update_rover()
# Run controller
if self._step_count % self._control_interval == 0:
self._run_controller()
# Apply physics
self._apply_controls()
p.stepSimulation()
self._step_count += 1
self._time += self._timestep
# Check landing
if self._check_landing():
print("\n*** LANDING SUCCESSFUL! ***\n")
time.sleep(2)
break
# Timing
elapsed = time.time() - loop_start
sleep_time = self._timestep - elapsed
if sleep_time > 0:
time.sleep(sleep_time)
except KeyboardInterrupt:
print("\nStopping simulation...")
finally:
if p.isConnected():
p.disconnect()
def _update_rover(self) -> None:
"""Move the rover based on pattern."""
dt = self._timestep
if self._rover_pattern == 'stationary':
return
elif self._rover_pattern == 'linear':
omega = self._rover_speed / self._rover_amplitude
target_x = self._rover_amplitude * math.sin(omega * self._time)
self._rover_pos[0] += 2.0 * (target_x - self._rover_pos[0]) * dt
elif self._rover_pattern == 'circular':
omega = self._rover_speed / self._rover_amplitude
target_x = self._rover_amplitude * math.cos(omega * self._time)
target_y = self._rover_amplitude * math.sin(omega * self._time)
self._rover_pos[0] += 2.0 * (target_x - self._rover_pos[0]) * dt
self._rover_pos[1] += 2.0 * (target_y - self._rover_pos[1]) * dt
elif self._rover_pattern == 'square':
segment = int(self._time / 3) % 4
corners = [(1, 1), (-1, 1), (-1, -1), (1, -1)]
target = corners[segment]
target_x = target[0] * self._rover_amplitude
target_y = target[1] * self._rover_amplitude
dx = target_x - self._rover_pos[0]
dy = target_y - self._rover_pos[1]
dist = math.sqrt(dx**2 + dy**2)
if dist > 0.01:
self._rover_pos[0] += self._rover_speed * dx / dist * dt
self._rover_pos[1] += self._rover_speed * dy / dist * dt
# Update rover position in simulation
p.resetBasePositionAndOrientation(
self._rover_id,
[self._rover_pos[0], self._rover_pos[1], self._rover_pos[2]],
[0, 0, 0, 1]
)
def _get_telemetry(self) -> Dict[str, Any]:
"""Get current drone state."""
pos, orn = p.getBasePositionAndOrientation(self._drone_id)
vel, ang_vel = p.getBaseVelocity(self._drone_id)
euler = p.getEulerFromQuaternion(orn)
# Landing pad detection
dx = self._rover_pos[0] - pos[0]
dy = self._rover_pos[1] - pos[1]
dz = self._rover_pos[2] - pos[2]
horizontal_dist = math.sqrt(dx**2 + dy**2)
vertical_dist = -dz
landing_pad = None
if vertical_dist > 0 and vertical_dist < 10.0:
fov_rad = math.radians(self._camera_fov / 2)
max_horizontal = vertical_dist * math.tan(fov_rad)
if horizontal_dist < max_horizontal:
landing_pad = {
"relative_x": dx,
"relative_y": dy,
"distance": vertical_dist,
"confidence": 1.0 - (horizontal_dist / max_horizontal)
}
return {
"altimeter": {"altitude": pos[2], "vertical_velocity": vel[2]},
"velocity": {"x": vel[0], "y": vel[1], "z": vel[2]},
"imu": {
"orientation": {"roll": euler[0], "pitch": euler[1], "yaw": euler[2]},
"angular_velocity": {"x": ang_vel[0], "y": ang_vel[1], "z": ang_vel[2]}
},
"landing_pad": landing_pad,
"rover_position": {"x": self._rover_pos[0], "y": self._rover_pos[1]}
}
def _run_controller(self) -> None:
"""Simple landing controller."""
telemetry = self._get_telemetry()
altimeter = telemetry['altimeter']
altitude = altimeter['altitude']
vertical_vel = altimeter['vertical_velocity']
velocity = telemetry['velocity']
vel_x = velocity['x']
vel_y = velocity['y']
landing_pad = telemetry['landing_pad']
# Altitude control
target_alt = 0.0
thrust = self._Kp_z * (target_alt - altitude) - self._Kd_z * vertical_vel
# Horizontal control
if landing_pad is not None:
target_x = landing_pad['relative_x']
target_y = landing_pad['relative_y']
pitch = self._Kp_xy * target_x - self._Kd_xy * vel_x
roll = self._Kp_xy * target_y - self._Kd_xy * vel_y
else:
pitch = -self._Kd_xy * vel_x
roll = -self._Kd_xy * vel_y
# Clamp
thrust = max(-1.0, min(1.0, thrust))
pitch = max(-0.5, min(0.5, pitch))
roll = max(-0.5, min(0.5, roll))
self._command = {'thrust': thrust, 'pitch': pitch, 'roll': roll, 'yaw': 0.0}
def _apply_controls(self) -> None:
"""Apply control commands to drone."""
pos, orn = p.getBasePositionAndOrientation(self._drone_id)
rot_matrix = p.getMatrixFromQuaternion(orn)
local_up = [rot_matrix[2], rot_matrix[5], rot_matrix[8]]
total_thrust = self._hover_thrust + (self._command['thrust'] * self._thrust_scale)
total_thrust = max(0, total_thrust)
thrust_force = [
local_up[0] * total_thrust,
local_up[1] * total_thrust,
local_up[2] * total_thrust
]
p.applyExternalForce(
self._drone_id, -1,
forceObj=thrust_force,
posObj=pos,
flags=p.WORLD_FRAME
)
p.applyExternalTorque(
self._drone_id, -1,
torqueObj=[
self._command['pitch'] * self._pitch_torque_scale,
self._command['roll'] * self._roll_torque_scale,
self._command['yaw'] * self._yaw_torque_scale
],
flags=p.LINK_FRAME
)
def _check_landing(self) -> bool:
"""Check if drone landed on rover."""
contacts = p.getContactPoints(bodyA=self._drone_id, bodyB=self._rover_id)
if len(contacts) > 0:
vel, _ = p.getBaseVelocity(self._drone_id)
speed = math.sqrt(vel[0]**2 + vel[1]**2 + vel[2]**2)
return speed < self._landing_velocity
return False
def main():
parser = argparse.ArgumentParser(description='Standalone Drone Simulation')
parser.add_argument('--pattern', '-p', type=str, default='stationary',
choices=['stationary', 'linear', 'circular', 'square'],
help='Rover movement pattern')
parser.add_argument('--speed', '-s', type=float, default=0.5,
help='Rover speed in m/s')
parser.add_argument('--amplitude', '-a', type=float, default=2.0,
help='Rover movement amplitude in meters')
args = parser.parse_args()
sim = StandaloneSimulation(
rover_pattern=args.pattern,
rover_speed=args.speed,
rover_amplitude=args.amplitude
)
sim.run()
if __name__ == '__main__':
main()