Source code for isaaclab_contrib.controllers.lee_position_control_cfg

# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

from dataclasses import MISSING

from isaaclab.utils.configclass import configclass

from .lee_controller_base_cfg import LeeControllerBaseCfg
from .lee_position_control import LeePosController


[docs] @configclass class LeePosControllerCfg(LeeControllerBaseCfg): """Configuration for a Lee-style geometric quadrotor position controller. Unless otherwise noted, vectors are ordered as (x, y, z) in the simulation world/body frames. The position controller gains are sampled uniformly per environment between their corresponding ``*_min`` and ``*_max`` bounds at reset. """ class_type: type = LeePosController """The class type for the position controller.""" K_pos_range: tuple[tuple[float, float, float], tuple[float, float, float]] = MISSING """Position error proportional gain range about body axes [unitless]. This is a tuple of two tuples containing the minimum and maximum gains for each axis (x, y, z). Format: ((min_x, min_y, min_z), (max_x, max_y, max_z)) Example: ((3.0, 3.0, 2.0), (4.0, 4.0, 2.5)) for ARL Robot 1 """ K_vel_range: tuple[tuple[float, float, float], tuple[float, float, float]] = MISSING """Velocity error proportional gain range about body axes [unitless]. This is a tuple of two tuples containing the minimum and maximum gains for each axis (x, y, z). Format: ((min_x, min_y, min_z), (max_x, max_y, max_z)) Example: ((2.5, 2.5, 1.5), (3.5, 3.5, 2.0)) for ARL Robot 1 """