Quadruped Robots [omni.isaac.quadruped]

Quadruped Controller

class A1QPController(name: str, _simulate_dt: float, waypoint_pose=None)

[summary]

A1 QP controller as a layer.

An implementation of the QP controller[1]

References

[1] Bledt, Gerardo, et al. “MIT Cheetah 3: Design and control of a robust, dynamic quadruped robot.”

2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS). IEEE, 2018.

advance(dt: float, measurement: omni.isaac.quadruped.utils.a1_classes.A1Measurement, path_follow=False, auto_start=True) numpy.array

[summary]

Perform torque command generation.

Parameters
  • world. (dt {float} -- Timestep update in the) –

  • robot. (measurement {A1Measurement} -- Current measurement from) –

  • in (path_follow {bool} -- True if a waypoint is pathed) –

  • not (false if) –

  • automatically (auto_start {bool} -- True to start trotting after 1 second) –

  • pressed (False for start trotting after "Enter" is) –

Returns

np.ndarray – The desired joint torques for the robot.

ctrl_state_reset() None

[summary]

reset _ctrl_states and _ctrl_params to non-default values

reset() numpy.ndarray

[summary]

Reset the ctrl states.

set_target_command(base_command: Union[List[float], numpy.ndarray]) None

[summary]

Set target base velocity command from joystick

Parameters
  • base_command{Union[List[float]

  • robot (np.ndarray} -- velocity commands for the) –

setup() None

[summary]

Reset the ctrl states.

switch_mode()

[summary]

toggle between stationary/moving mode

update(dt: float, measurement: omni.isaac.quadruped.utils.a1_classes.A1Measurement)

[summary]

Fill measurement into _ctrl_states :param dt {float} – Timestep update in the world.: :param measurement {A1Measurement} – Current measurement from robot.:

class A1RobotControl

[summary]

The A1 robot controller This class uses A1CtrlStates to save data. The control joint torque is generated using a QP controller

generate_ctrl(desired_states: omni.isaac.quadruped.utils.a1_desired_states.A1DesiredStates, input_states: omni.isaac.quadruped.utils.a1_ctrl_states.A1CtrlStates, input_params: omni.isaac.quadruped.utils.a1_ctrl_params.A1CtrlParams) None

[summary]

main function, generate foot ground reaction force using QP and calculate joint torques

Parameters
  • states (input_states {A1CtrlStates} -- the control) –

  • states

  • parameters (input_params {A1CtrlParams} -- the control) –

update_plan(desired_states: omni.isaac.quadruped.utils.a1_desired_states.A1DesiredStates, input_states: omni.isaac.quadruped.utils.a1_ctrl_states.A1CtrlStates, input_params: omni.isaac.quadruped.utils.a1_ctrl_params.A1CtrlParams, dt: float) None

[summary]

update swing leg trajectory and several counters

Parameters
  • states (input_states {A1CtrlStates} -- the control) –

  • states

  • parameters (input_params {A1CtrlParams} -- the control) –

  • time-step. (dt {float} -- The simulation) –

Quadruped Robots

class Anymal(prim_path: str, name: str = 'anymal', usd_path: Optional[str] = None, position: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None)

The ANYmal quadruped

advance(dt, command)

[summary]

compute the desired torques and apply them to the articulation

Argument: dt {float} – Timestep update in the world. command {np.ndarray} – the robot command (v_x, v_y, w_z)

apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None

[summary]

Parameters
  • control_actions (ArticulationAction) – actions to be applied for next physics step.

  • indices (Optional[Union[list, np.ndarray]], optional) – degree of freedom indices to apply actions to. Defaults to all degrees of freedom.

Raises

Exception – [description]

apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Used to apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

property articulation_handle: int

[summary]

Returns

[description]

Return type

int

disable_gravity() None

Keep gravity from affecting the robot

property dof_names: List[str]

List of prim names for each DOF.

Returns

prim names

Return type

list(string)

property dof_properties: numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

enable_gravity() None

Gravity will affect the robot

get_angular_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_applied_action() omni.isaac.core.utils.types.ArticulationAction

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

ArticulationAction

get_applied_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the efforts applied to the joints

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_applied_visual_material() omni.isaac.core.materials.visual_material.VisualMaterial
Returns the current applied visual material in case it was applied using apply_visual_material OR

it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.

Returns

the current applied visual material if its type is currently supported.

Return type

VisualMaterial

get_articulation_body_count() int

[summary]

Returns

[description]

Return type

int

get_articulation_controller() omni.isaac.core.controllers.articulation_controller.ArticulationController
Returns

PD Controller of all degrees of freedom of an articulation, can apply position targets, velocity targets and efforts.

Return type

ArticulationController

get_default_state() omni.isaac.core.utils.types.XFormPrimState
Returns

returns the default state of the prim (position and orientation) that is used after each reset.

Return type

XFormPrimState

get_dof_index(dof_name: str) int

[summary]

Parameters

dof_name (str) – [description]

Returns

[description]

Return type

int

get_enabled_self_collisions() bool

[summary]

Returns

[description]

Return type

bool

get_joint_positions(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joint_velocities(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joints_default_state() omni.isaac.core.utils.types.JointsState

Accessor for the default joints state.

Returns

The defaults that the robot is reset to when post_reset() is called (often automatically called during world.reset()).

Return type

JointsState

get_joints_state() omni.isaac.core.utils.types.JointsState

[summary]

Returns

[description]

Return type

JointsState

get_linear_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the local frame (the prim’s parent frame).

Returns

first index is position in the local frame of the prim. shape is (3, ).

second index is quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

Gets prim’s scale with respect to the local frame (the parent’s frame).

Returns

scale applied to the prim’s dimensions in the local frame. shape is (3, ).

Return type

np.ndarray

get_measured_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Returns the dof efforts computed/measured by the physics solver

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_measured_joint_forces(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the measured joint forces

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_sleep_threshold() float

[summary]

Returns

[description]

Return type

float

get_solver_position_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_solver_velocity_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_stabilization_threshold() float

[summary]

Returns

[description]

Return type

float

get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the world’s frame.

Returns

first index is position in the world frame of the prim. shape is (3, ).

second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

Gets prim’s scale with respect to the world’s frame.

Returns

scale applied to the prim’s dimensions in the world frame. shape is (3, ).

Return type

np.ndarray

property handles_initialized: bool

[summary]

Returns

[description]

Return type

bool

initialize(physics_sim_view=None) None

[summary]

initialize the dc interface, set up drive mode

is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

is_visual_material_applied() bool
Returns

True if there is a visual material applied. False otherwise.

Return type

bool

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

_summary_

Returns

_description_

Return type

bool

property num_dof: int

[summary]

Returns

[description]

Return type

int

post_reset() None

[summary]

post reset articulation

property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage.

set_angular_velocity(velocity: numpy.ndarray) None

[summary]

Parameters

velocity (np.ndarray) – [description]

set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets the default state of the prim (position and orientation), that will be used after each reset.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_enabled_self_collisions(flag: bool) None

[summary]

Parameters

flag (bool) – [description]

set_joint_efforts(efforts: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • efforts (np.ndarray) – [description]

  • joint_indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_positions(positions: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • positions (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_velocities(velocities: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • velocities (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joints_default_state(positions: Optional[numpy.ndarray] = None, velocities: Optional[numpy.ndarray] = None, efforts: Optional[numpy.ndarray] = None) None

[summary]

Parameters
  • positions (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • velocities (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • efforts (Optional[np.ndarray], optional) – [description]. Defaults to None.

set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage.

Parameters

velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).

set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the local frame (the prim’s parent frame).

Parameters
  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_local_scale(scale: Optional[Sequence[float]]) None

Sets prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

set_sleep_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_solver_position_iteration_count(count: int) None

[summary]

Parameters

count (int) – [description]

set_solver_velocity_iteration_count(count: int)

[summary]

Parameters

count (int) – [description]

set_stabilization_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

visible (bool) – flag to set the visibility of the usd prim in stage.

set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the world’s frame.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

class Unitree(prim_path: str, name: str = 'unitree_quadruped', physics_dt: Optional[float] = 0.0025, usd_path: Optional[str] = None, position: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, model: Optional[str] = 'A1', way_points: Optional[numpy.ndarray] = None)

For unitree based quadrupeds (A1 or Go1)

advance(dt, goal, path_follow=False, auto_start=True) numpy.ndarray

[summary]

compute desired torque and set articulation effort to robot joints

Argument: dt {float} – Timestep update in the world. goal {List[int]} – x velocity, y velocity, angular velocity, state switch path_follow {bool} – true for following coordinates, false for keyboard control auto_start {bool} – true for start trotting after 1 sec, false for start trotting after switch mode function is called

Returns: np.ndarray – The desired joint torques for the robot.

apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None

[summary]

Parameters
  • control_actions (ArticulationAction) – actions to be applied for next physics step.

  • indices (Optional[Union[list, np.ndarray]], optional) – degree of freedom indices to apply actions to. Defaults to all degrees of freedom.

Raises

Exception – [description]

apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Used to apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

property articulation_handle: int

[summary]

Returns

[description]

Return type

int

disable_gravity() None

Keep gravity from affecting the robot

property dof_names: List[str]

List of prim names for each DOF.

Returns

prim names

Return type

list(string)

property dof_properties: numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

enable_gravity() None

Gravity will affect the robot

get_angular_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_applied_action() omni.isaac.core.utils.types.ArticulationAction

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

ArticulationAction

get_applied_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the efforts applied to the joints

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_applied_visual_material() omni.isaac.core.materials.visual_material.VisualMaterial
Returns the current applied visual material in case it was applied using apply_visual_material OR

it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.

Returns

the current applied visual material if its type is currently supported.

Return type

VisualMaterial

get_articulation_body_count() int

[summary]

Returns

[description]

Return type

int

get_articulation_controller() omni.isaac.core.controllers.articulation_controller.ArticulationController
Returns

PD Controller of all degrees of freedom of an articulation, can apply position targets, velocity targets and efforts.

Return type

ArticulationController

get_default_state() omni.isaac.core.utils.types.XFormPrimState
Returns

returns the default state of the prim (position and orientation) that is used after each reset.

Return type

XFormPrimState

get_dof_index(dof_name: str) int

[summary]

Parameters

dof_name (str) – [description]

Returns

[description]

Return type

int

get_enabled_self_collisions() bool

[summary]

Returns

[description]

Return type

bool

get_joint_positions(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joint_velocities(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joints_default_state() omni.isaac.core.utils.types.JointsState

Accessor for the default joints state.

Returns

The defaults that the robot is reset to when post_reset() is called (often automatically called during world.reset()).

Return type

JointsState

get_joints_state() omni.isaac.core.utils.types.JointsState

[summary]

Returns

[description]

Return type

JointsState

get_linear_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the local frame (the prim’s parent frame).

Returns

first index is position in the local frame of the prim. shape is (3, ).

second index is quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

Gets prim’s scale with respect to the local frame (the parent’s frame).

Returns

scale applied to the prim’s dimensions in the local frame. shape is (3, ).

Return type

np.ndarray

get_measured_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Returns the dof efforts computed/measured by the physics solver

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_measured_joint_forces(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the measured joint forces

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_sleep_threshold() float

[summary]

Returns

[description]

Return type

float

get_solver_position_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_solver_velocity_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_stabilization_threshold() float

[summary]

Returns

[description]

Return type

float

get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the world’s frame.

Returns

first index is position in the world frame of the prim. shape is (3, ).

second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

Gets prim’s scale with respect to the world’s frame.

Returns

scale applied to the prim’s dimensions in the world frame. shape is (3, ).

Return type

np.ndarray

property handles_initialized: bool

[summary]

Returns

[description]

Return type

bool

initialize(physics_sim_view=None) None

[summary]

initialize dc interface, set up drive mode and initial robot state

is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

is_visual_material_applied() bool
Returns

True if there is a visual material applied. False otherwise.

Return type

bool

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

_summary_

Returns

_description_

Return type

bool

property num_dof: int

[summary]

Returns

[description]

Return type

int

post_reset() None

[summary]

post reset articulation and qp_controller

property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage.

set_angular_velocity(velocity: numpy.ndarray) None

[summary]

Parameters

velocity (np.ndarray) – [description]

set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets the default state of the prim (position and orientation), that will be used after each reset.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_enabled_self_collisions(flag: bool) None

[summary]

Parameters

flag (bool) – [description]

set_joint_efforts(efforts: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • efforts (np.ndarray) – [description]

  • joint_indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_positions(positions: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • positions (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_velocities(velocities: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • velocities (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joints_default_state(positions: Optional[numpy.ndarray] = None, velocities: Optional[numpy.ndarray] = None, efforts: Optional[numpy.ndarray] = None) None

[summary]

Parameters
  • positions (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • velocities (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • efforts (Optional[np.ndarray], optional) – [description]. Defaults to None.

set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage.

Parameters

velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).

set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the local frame (the prim’s parent frame).

Parameters
  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_local_scale(scale: Optional[Sequence[float]]) None

Sets prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

set_sleep_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_solver_position_iteration_count(count: int) None

[summary]

Parameters

count (int) – [description]

set_solver_velocity_iteration_count(count: int)

[summary]

Parameters

count (int) – [description]

set_stabilization_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_state(state: omni.isaac.quadruped.utils.a1_classes.A1State) None

[Summary]

Set the kinematic state of the robot.

Parameters

set. (state {A1State} -- The state of the robot to) –

Raises

RuntimeError – When the DC Toolbox interface has not been configured.

set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

visible (bool) – flag to set the visibility of the usd prim in stage.

set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the world’s frame.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

update() None

[summary]

update robot sensor variables, state variables in A1Measurement

update_contact_sensor_data() None

[summary]

Updates processed contact sensor data from the robot feets, store them in member variable foot_force

update_imu_sensor_data() None

[summary]

Updates processed imu sensor data from the robot body, store them in member variable base_lin and ang_vel

class UnitreeDirect(prim_path: str, name: str = 'unitree_quadruped_ROS', physics_dt: Optional[float] = 0.0025, usd_path: Optional[str] = None, position: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, model: Optional[str] = 'A1')

For unitree based quadrupeds (A1 or Go1) This class only read command from an external torque and send the torque command to the articulation directly, perhaps a external ROS node generates the command

advance()

[summary]

direct control the robot using desired_joint_torque

Argument: dt {float} – Timestep update in the world. goal {List[int]} – x velocity, y velocity, angular velocity, state switch

Returns: np.ndarray – The desired joint torques for the robot.

apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None

[summary]

Parameters
  • control_actions (ArticulationAction) – actions to be applied for next physics step.

  • indices (Optional[Union[list, np.ndarray]], optional) – degree of freedom indices to apply actions to. Defaults to all degrees of freedom.

Raises

Exception – [description]

apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Used to apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

property articulation_handle: int

[summary]

Returns

[description]

Return type

int

disable_gravity() None

Keep gravity from affecting the robot

property dof_names: List[str]

List of prim names for each DOF.

Returns

prim names

Return type

list(string)

property dof_properties: numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

enable_gravity() None

Gravity will affect the robot

get_angular_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_applied_action() omni.isaac.core.utils.types.ArticulationAction

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

ArticulationAction

get_applied_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the efforts applied to the joints

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_applied_visual_material() omni.isaac.core.materials.visual_material.VisualMaterial
Returns the current applied visual material in case it was applied using apply_visual_material OR

it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.

Returns

the current applied visual material if its type is currently supported.

Return type

VisualMaterial

get_articulation_body_count() int

[summary]

Returns

[description]

Return type

int

get_articulation_controller() omni.isaac.core.controllers.articulation_controller.ArticulationController
Returns

PD Controller of all degrees of freedom of an articulation, can apply position targets, velocity targets and efforts.

Return type

ArticulationController

get_default_state() omni.isaac.core.utils.types.XFormPrimState
Returns

returns the default state of the prim (position and orientation) that is used after each reset.

Return type

XFormPrimState

get_dof_index(dof_name: str) int

[summary]

Parameters

dof_name (str) – [description]

Returns

[description]

Return type

int

get_enabled_self_collisions() bool

[summary]

Returns

[description]

Return type

bool

get_joint_positions(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joint_velocities(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joints_default_state() omni.isaac.core.utils.types.JointsState

Accessor for the default joints state.

Returns

The defaults that the robot is reset to when post_reset() is called (often automatically called during world.reset()).

Return type

JointsState

get_joints_state() omni.isaac.core.utils.types.JointsState

[summary]

Returns

[description]

Return type

JointsState

get_linear_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the local frame (the prim’s parent frame).

Returns

first index is position in the local frame of the prim. shape is (3, ).

second index is quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

Gets prim’s scale with respect to the local frame (the parent’s frame).

Returns

scale applied to the prim’s dimensions in the local frame. shape is (3, ).

Return type

np.ndarray

get_measured_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Returns the dof efforts computed/measured by the physics solver

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_measured_joint_forces(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the measured joint forces

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_sleep_threshold() float

[summary]

Returns

[description]

Return type

float

get_solver_position_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_solver_velocity_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_stabilization_threshold() float

[summary]

Returns

[description]

Return type

float

get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the world’s frame.

Returns

first index is position in the world frame of the prim. shape is (3, ).

second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

Gets prim’s scale with respect to the world’s frame.

Returns

scale applied to the prim’s dimensions in the world frame. shape is (3, ).

Return type

np.ndarray

property handles_initialized: bool

[summary]

Returns

[description]

Return type

bool

initialize(physics_sim_view=None) None

[summary]

initialize dc interface, set up drive mode and initial robot state

is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

is_visual_material_applied() bool
Returns

True if there is a visual material applied. False otherwise.

Return type

bool

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

_summary_

Returns

_description_

Return type

bool

property num_dof: int

[summary]

Returns

[description]

Return type

int

post_reset() None

[summary]

post reset articulation and qp_controller

property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage.

set_angular_velocity(velocity: numpy.ndarray) None

[summary]

Parameters

velocity (np.ndarray) – [description]

set_command_torque(_desired_joint_torque) None

Allow external nodes directly set robot command torque

_desired_joint_torque should be a 12x1 vector of torques

set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets the default state of the prim (position and orientation), that will be used after each reset.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_enabled_self_collisions(flag: bool) None

[summary]

Parameters

flag (bool) – [description]

set_joint_efforts(efforts: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • efforts (np.ndarray) – [description]

  • joint_indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_positions(positions: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • positions (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_velocities(velocities: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • velocities (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joints_default_state(positions: Optional[numpy.ndarray] = None, velocities: Optional[numpy.ndarray] = None, efforts: Optional[numpy.ndarray] = None) None

[summary]

Parameters
  • positions (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • velocities (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • efforts (Optional[np.ndarray], optional) – [description]. Defaults to None.

set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage.

Parameters

velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).

set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the local frame (the prim’s parent frame).

Parameters
  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_local_scale(scale: Optional[Sequence[float]]) None

Sets prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

set_sleep_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_solver_position_iteration_count(count: int) None

[summary]

Parameters

count (int) – [description]

set_solver_velocity_iteration_count(count: int)

[summary]

Parameters

count (int) – [description]

set_stabilization_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_state(state: omni.isaac.quadruped.utils.a1_classes.A1State) None

[Summary]

Set the kinematic state of the robot.

Parameters

set. (state {A1State} -- The state of the robot to) –

Raises

RuntimeError – When the DC Toolbox interface has not been configured.

set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

visible (bool) – flag to set the visibility of the usd prim in stage.

set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the world’s frame.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

update()

[summary]

update robot sensor variables, state variables in A1Measurement

update_contact_sensor_data() None

[summary]

Updates processed contact sensor data from the robot feets, store them in member variable foot_force

update_imu_sensor_data()

[summary]

Updates processed imu sensor data from the robot body, store them in member variable base_lin and ang_vel

class UnitreeVision(prim_path: str, name: str = 'unitree_quadruped', physics_dt: Optional[float] = 0.0025, usd_path: Optional[str] = None, position: Optional[numpy.ndarray] = None, orientation: Optional[numpy.ndarray] = None, model: Optional[str] = 'A1', is_ros2: Optional[bool] = False, way_points: Optional[numpy.ndarray] = None)

[Summary]

For unitree based quadrupeds (A1 or Go1) with camera

advance(dt, goal, path_follow=False) numpy.ndarray

[summary]

calls the unitree advance to compute torque

Argument: dt {float} – Timestep update in the world. goal {List[int]} – x velocity, y velocity, angular velocity, state switch path_follow {bool} – True for following a set of coordinates, False for keyboard control

Returns: np.ndarray – The desired joint torques for the robot.

apply_action(control_actions: omni.isaac.core.utils.types.ArticulationAction) None

[summary]

Parameters
  • control_actions (ArticulationAction) – actions to be applied for next physics step.

  • indices (Optional[Union[list, np.ndarray]], optional) – degree of freedom indices to apply actions to. Defaults to all degrees of freedom.

Raises

Exception – [description]

apply_visual_material(visual_material: omni.isaac.core.materials.visual_material.VisualMaterial, weaker_than_descendants: bool = False) None

Used to apply visual material to the held prim and optionally its descendants.

Parameters
  • visual_material (VisualMaterial) – visual material to be applied to the held prim. Currently supports PreviewSurface, OmniPBR and OmniGlass.

  • weaker_than_descendants (bool, optional) – True if the material shouldn’t override the descendants materials, otherwise False. Defaults to False.

property articulation_handle: int

[summary]

Returns

[description]

Return type

int

disable_gravity() None

Keep gravity from affecting the robot

dockViewports() None

[Summary]

For instantiating and docking view ports

property dof_names: List[str]

List of prim names for each DOF.

Returns

prim names

Return type

list(string)

property dof_properties: numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

enable_gravity() None

Gravity will affect the robot

get_angular_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_applied_action() omni.isaac.core.utils.types.ArticulationAction

[summary]

Raises

Exception – [description]

Returns

[description]

Return type

ArticulationAction

get_applied_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the efforts applied to the joints

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_applied_visual_material() omni.isaac.core.materials.visual_material.VisualMaterial
Returns the current applied visual material in case it was applied using apply_visual_material OR

it’s one of the following materials that was already applied before: PreviewSurface, OmniPBR and OmniGlass.

Returns

the current applied visual material if its type is currently supported.

Return type

VisualMaterial

get_articulation_body_count() int

[summary]

Returns

[description]

Return type

int

get_articulation_controller() omni.isaac.core.controllers.articulation_controller.ArticulationController
Returns

PD Controller of all degrees of freedom of an articulation, can apply position targets, velocity targets and efforts.

Return type

ArticulationController

get_default_state() omni.isaac.core.utils.types.XFormPrimState
Returns

returns the default state of the prim (position and orientation) that is used after each reset.

Return type

XFormPrimState

get_dof_index(dof_name: str) int

[summary]

Parameters

dof_name (str) – [description]

Returns

[description]

Return type

int

get_enabled_self_collisions() bool

[summary]

Returns

[description]

Return type

bool

get_joint_positions(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joint_velocities(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

_summary_

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Returns

_description_

Return type

np.ndarray

get_joints_default_state() omni.isaac.core.utils.types.JointsState

Accessor for the default joints state.

Returns

The defaults that the robot is reset to when post_reset() is called (often automatically called during world.reset()).

Return type

JointsState

get_joints_state() omni.isaac.core.utils.types.JointsState

[summary]

Returns

[description]

Return type

JointsState

get_linear_velocity() numpy.ndarray

[summary]

Returns

[description]

Return type

np.ndarray

get_local_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the local frame (the prim’s parent frame).

Returns

first index is position in the local frame of the prim. shape is (3, ).

second index is quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_local_scale() numpy.ndarray

Gets prim’s scale with respect to the local frame (the parent’s frame).

Returns

scale applied to the prim’s dimensions in the local frame. shape is (3, ).

Return type

np.ndarray

get_measured_joint_efforts(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Returns the dof efforts computed/measured by the physics solver

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_measured_joint_forces(joint_indices: Optional[Union[List, numpy.ndarray]] = None) numpy.ndarray

Gets the measured joint forces

Parameters

joint_indices (Optional[Union[List, np.ndarray]], optional) – _description_. Defaults to None.

Raises

Exception – _description_

Returns

_description_

Return type

np.ndarray

get_sleep_threshold() float

[summary]

Returns

[description]

Return type

float

get_solver_position_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_solver_velocity_iteration_count() int

[summary]

Returns

[description]

Return type

int

get_stabilization_threshold() float

[summary]

Returns

[description]

Return type

float

get_visibility() bool
Returns

true if the prim is visible in stage. false otherwise.

Return type

bool

get_world_pose() Tuple[numpy.ndarray, numpy.ndarray]

Gets prim’s pose with respect to the world’s frame.

Returns

first index is position in the world frame of the prim. shape is (3, ).

second index is quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ).

Return type

Tuple[np.ndarray, np.ndarray]

get_world_scale() numpy.ndarray

Gets prim’s scale with respect to the world’s frame.

Returns

scale applied to the prim’s dimensions in the world frame. shape is (3, ).

Return type

np.ndarray

property handles_initialized: bool

[summary]

Returns

[description]

Return type

bool

initialize(physics_sim_view=None) None

[summary]

initialize dc interface, set up drive mode and initial robot state

is_valid() bool
Returns

True is the current prim path corresponds to a valid prim in stage. False otherwise.

Return type

bool

is_visual_material_applied() bool
Returns

True if there is a visual material applied. False otherwise.

Return type

bool

property name: Optional[str]

Returns: str: name given to the prim when instantiating it. Otherwise None.

_summary_

Returns

_description_

Return type

bool

property num_dof: int

[summary]

Returns

[description]

Return type

int

post_reset() None

[summary]

post reset articulation and qp_controller

property prim: pxr.Usd.Prim

Returns: Usd.Prim: USD Prim object that this object holds.

property prim_path: str

Returns: str: prim path in the stage.

setCameraExeutionStep(step: numpy.uint64) None

[Summary]

Sets the execution step in the omni.isaac.core_nodes.IsaacSimulationGate node located in the camera sensor pipeline

set_angular_velocity(velocity: numpy.ndarray) None

[summary]

Parameters

velocity (np.ndarray) – [description]

set_default_state(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets the default state of the prim (position and orientation), that will be used after each reset.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_enabled_self_collisions(flag: bool) None

[summary]

Parameters

flag (bool) – [description]

set_joint_efforts(efforts: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • efforts (np.ndarray) – [description]

  • joint_indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_positions(positions: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • positions (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joint_velocities(velocities: numpy.ndarray, joint_indices: Optional[Union[List, numpy.ndarray]] = None) None

[summary]

Parameters
  • velocities (np.ndarray) – [description]

  • indices (Optional[Union[list, np.ndarray]], optional) – [description]. Defaults to None.

Raises

Exception – [description]

set_joints_default_state(positions: Optional[numpy.ndarray] = None, velocities: Optional[numpy.ndarray] = None, efforts: Optional[numpy.ndarray] = None) None

[summary]

Parameters
  • positions (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • velocities (Optional[np.ndarray], optional) – [description]. Defaults to None.

  • efforts (Optional[np.ndarray], optional) – [description]. Defaults to None.

set_linear_velocity(velocity: numpy.ndarray)

Sets the linear velocity of the prim in stage.

Parameters

velocity (np.ndarray) – linear velocity to set the rigid prim to. Shape (3,).

set_local_pose(translation: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the local frame (the prim’s parent frame).

Parameters
  • translation (Optional[Sequence[float]], optional) – translation in the local frame of the prim (with respect to its parent prim). shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the local frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

set_local_scale(scale: Optional[Sequence[float]]) None

Sets prim’s scale with respect to the local frame (the prim’s parent frame).

Parameters

scale (Optional[Sequence[float]]) – scale to be applied to the prim’s dimensions. shape is (3, ). Defaults to None, which means left unchanged.

set_sleep_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_solver_position_iteration_count(count: int) None

[summary]

Parameters

count (int) – [description]

set_solver_velocity_iteration_count(count: int)

[summary]

Parameters

count (int) – [description]

set_stabilization_threshold(threshold: float) None

[summary]

Parameters

threshold (float) – [description]

set_state(state: omni.isaac.quadruped.utils.a1_classes.A1State) None

[Summary]

Set the kinematic state of the robot.

Parameters

set. (state {A1State} -- The state of the robot to) –

Raises

RuntimeError – When the DC Toolbox interface has not been configured.

set_visibility(visible: bool) None

Sets the visibility of the prim in stage.

Parameters

visible (bool) – flag to set the visibility of the usd prim in stage.

set_world_pose(position: Optional[Sequence[float]] = None, orientation: Optional[Sequence[float]] = None) None

Sets prim’s pose with respect to the world’s frame.

Parameters
  • position (Optional[Sequence[float]], optional) – position in the world frame of the prim. shape is (3, ). Defaults to None, which means left unchanged.

  • orientation (Optional[Sequence[float]], optional) – quaternion orientation in the world frame of the prim. quaternion is scalar-first (w, x, y, z). shape is (4, ). Defaults to None, which means left unchanged.

update() None

[Summary]

Update robot variables from the environment

update_contact_sensor_data() None

[summary]

Updates processed contact sensor data from the robot feets, store them in member variable foot_force

update_imu_sensor_data() None

[summary]

Updates processed imu sensor data from the robot body, store them in member variable base_lin and ang_vel

Quadruped Utilities