Crate peng_quad

Source
Expand description

§Peng - A Minimal Quadrotor Autonomy Framework

A high-performance quadrotor autonomy framework written in Rust that provides real-time dynamics simulation, trajectory planning, and control with modern visualization capabilities.

§Features

§Real-time Simulation

  • High-fidelity quadrotor dynamics with configurable parameters
  • IMU and depth sensor simulation
  • Optional RK4 integration for accurate dynamics

§Advanced Control

  • PID control for position and attitude with tunable gains
  • Integral windup prevention
  • Support for different control frequencies

§Rich Trajectory Planning

  • Minimum jerk line trajectory planner
  • Lissajous curve planner
  • Circular trajectory planner
  • Obstacle avoidance planner
  • Waypoint navigation planner
  • Landing planner

§Visualization & Debug

  • Real-time 3D visualization via rerun.io
  • Depth map rendering
  • State telemetry logging
  • Configurable logging frequencies

§Performance

  • Memory-safe and Efficient Rust implementation
  • Multi-threaded depth rendering

§Example

use nalgebra::Vector3;
use peng_quad::{Quadrotor, SimulationError};
let (time_step, mass, gravity, drag_coefficient) = (0.01, 1.3, 9.81, 0.01);
let inertia_matrix = [0.0347563, 0.0, 0.0, 0.0, 0.0458929, 0.0, 0.0, 0.0, 0.0977];
let quadrotor = Quadrotor::new(time_step, mass, gravity, drag_coefficient, inertia_matrix);

Modules§

config
Configuration module

Structs§

Camera
Represents a camera in the simulation which is used to render the depth of the scene
CirclePlanner
Planner for circular trajectories
HoverPlanner
Planner for hovering at a fixed position
Imu
Represents an Inertial Measurement Unit (IMU) with bias and noise characteristics
LandingPlanner
Planner for landing maneuvers
LissajousPlanner
Planner for Lissajous curve trajectories
Maze
Represents a maze in the simulation
MinimumJerkLinePlanner
Planner for minimum jerk trajectories along a straight line
MinimumSnapWaypointPlanner
Waypoint planner that generates a minimum snap trajectory between waypoints
Obstacle
Represents an obstacle in the simulation
ObstacleAvoidancePlanner
Obstacle avoidance planner that uses a potential field approach to avoid obstacles
PIDController
PID controller for quadrotor position and attitude control
PlannerManager
Manages different trajectory planners and switches between them
PlannerStepConfig
Represents a step in the planner schedule.
QPpolyTrajPlanner
Waypoint planner that generates a quadratic polynomial trajectory between waypoints
Quadrotor
Represents a quadrotor with its physical properties and state
Trajectory
A struct to hold trajectory data

Enums§

PlannerType
Enum representing different types of trajectory planners
SimulationError
Represents errors that can occur during simulation

Traits§

Planner
Trait defining the interface for trajectory planners

Functions§

color_map_fn
turbo color map function
create_planner
Creates a planner based on the configuration
log_data
Logs simulation data to the rerun recording stream
log_depth_image
Log depth image data to the rerun recording stream
log_maze_obstacles
Log the maze obstacles to the rerun recording stream
log_maze_tube
Log the maze tube to the rerun recording stream
log_pinhole_depth
creates pinhole camera
log_trajectory
log trajectory data to the rerun recording stream
parse_f32
Helper function to parse f32 from YAML
parse_usize
Helper function to parse unsigned integer from YAML
parse_vector3
Helper function to parse Vector3 from YAML
ray_cast
Casts a ray from the camera origin in the given direction
update_planner
Updates the planner based on the current simulation step and configuration