Tutorials written in the scripting language Python

All Python based tutorials can be found in <agxDir>/data/python/tutorials. Most of the scripts can be started both with the native python and agxViewer.
To run these tutorials, AGX needs to be installed on the computer. The .agxPy file suffix is associated to the application agxViewer which will be executed for the links below.

If you want to start one of the scripts manually in a command window, just write:

agxviewer tutorials\tutorial1_graphics.agxPy

agxViewer starts by default in paused mode. Remember to press 'e' to start simulation.

Press '1' to reload the scenes.

Keybindings and arguments for agxViewer

Tutorial: Basic simulation

Create a basic simulation with bodies, geometries and shapes. 

Shows how to:

  • Create a basic simulation with bodies, geometries and shapes.
  • Can be started with the native python or agxViewer application. However, no graphics is generated in this script, so when you start it with agxViewer, you need to press 'g' to see the geometry.
Tutorial0

Tutorial: Attaching graphical objects

Create bodies/geometries and attach rendering objects to each of them.

Shows how to: 

  • Create a simulation including graphics which is loadable with agxViewer.
  • Load a graphical object from a file, and connect it to a geometry so that it moves with the geometry.

This script can only be loaded with agxViewer, NOT python.

Tutorial1

Tutorial: Supporting both python and agxViewer

Create bodies/geometries and attach rendering objects to each of them.

Shows how to:  

Tutorial2

Tutorial: Events and reading forces

This tutorial show how to listen for simulation event and read forces from contacts and constraints.

Shows how to:

  • Create a StepEventListener to listen for events in the simulation loop
  • Access contact data/forces and write them to the screen
  • Get all constraints in a system
  • Access constraint data and read forces
  • Draw simple text onto the screen

Tutorial3

Tutorial: Creating objects during runtime

This script randomly creates objects during runtime.

Shows how to:

  • Use AutoSleep
  • Create a StepEventListener to listen for events in the simulation loop
  • Create and remove objects during runtime.
Tutorial4

Tutorial: Read scenes from file and transform objects using Assemblies

Shows how to:
  • Read simulation data from .aagx file
  • Group and move objects using agxSDK::Assembly
  • Get objects from an Assembly
  • Access data using names
Tutorial5

Tutorial: Mesh Reader

Shows how to:
  • Read a mesh file from disk and create a TriangleMesh shape for collision detection
  • Read a mesh file and use for rendering
Tutorial5

Tutorial: Read keyboard events. Change shapes


Shows how to:
  • agxSDK.GuiEventListener for listening to keyboard and mouse events
  • Change a shape in size (radius of a sphere), including the graphics
Tutorial6

Tutorial: Building deformable objects

Shows how to:

Build a "lumped" object by attaching bodies/constraint to each other

  • Set compliance to make lumped objects stiffer (all the way to infinite)
Tutorial9

Tutorial: Using iterative solver for contacts

Shows how to:

Use the iterative solver specified on a per-material basis. The iterative solver does not give the same precision as the direct, but is a lot faster for large contact/friction system.

Also by using the ParallelPgs solver good performance can be gained with more than 1 thread.

Iterative contact friction tutorial

Tutorial: Constraints

This tutorial demonstrates all the constraints available in AGX.


Constraints
                      tutorial

Tutorial: Tire model

This is a tutorial demonstrating how to use the TireModel class for simulating the wheels of a vehicle.

Control the car with up/down/left/right. If you have a gamepad connected it can be used to control the car.

Tire model tutorial

Tutorial: Hydraulic winch with plotting

Required licenses: agxHydraulics, agxWire

This script demonstrates how to build a hydraulic driven winch with wires. During simulation data will be plotted: rpm, pressure, flow etc.

Included in the tutorial is:

  • RPM controller (written in Python)
  • Engine
  • Hydraulic pump
  • Shafts
  • Relief valve
  • GearBox
  • Clutch
  • WireWinchActuator
Hydraulic
                              winch
Hydraulic winch

Tutorial: Cable

Required licenses: agxCables

This script contains several scenes where each illustrate how to use the agxCable api.

Press key 1..7 to choose scene. Shows how to:

  • Create and route a cable.
  • Attach cable to objects.
  • Set cable properties.
  • Inspect dynamic state.
  • Control initialization.
  • Detect cable collisions.
  • Attach objects on initialized cable.
Start tutorial_cable.agxPy in agxViewer
View source code
tutorial_cable

Tutorial: Cable Damage

Required licenses: agxCables

This script demonstrates how to setup and use the CableDamage class available in AGX Dynamics.

Cable damage can measure the accumulated strain in a cable tue to bend/twist/stretch

Start tutorial_cableDamage.agxPy in agxViewer
View source code
tutorial_cableDamage

Tutorial: Cable Tunneling Guard

Required licenses: agxCables

This script demonstrates how to setup and use the CableTunnelingGuard class available in AGX Dynamics and shows off a few examples of parameterizing the class to avoid certain types of tunneling.

Tunneling caused by low simulation frequencies can be reduced by using the CableTunnelingGuard class. It offers default values to suit many situations but also exposes parameters to more aggressively prevent tunneling, if needed.

Start tutorial_cable_tunneling_guard.agxPy in agxViewer
View source code
tutorial_cable_tunneling_guard

Tutorial: Fracture

This tutorial shows how to use the FractureGenerator class for breaking and fracturing geometries in the simulation using 3D Voronoi tessellation.

Press key 1..4 to choose scene.

Start tutorial_fracture.agxPy in agxViewer
View source code
tutorial_fracture

Tutorial: Gearbox

Required licenses: agxDriveTrain

This script demonstrates how to create a series of hinges with motors, where all hinge output shafts are connected to one gearbox. Resulting in one hinge driven by the resulting torque of the gearbox output shaft.

Increase/decrease torque using up/down keys

Start tutorial_gearbox.agxPy in agxViewer
View source code
tutorial_gearbox

Tutorial: Conveyor belt simulation

This scene demonstrates how to create a surface velocity conveyor belt # in order to set up a basic conveyor belt simulation transporting goods.

Start tutorial_surface_velocity_conveyor_belt.agxPy in agxViewer
View source code
tutorial_surface_velocity_conveyor_belt

Tutorial: Demonstration of various contact friction models

This scene demonstrates how to best make use of the various contact friction models available in AGX Dynamics

Start tutorial_direct_iterative_solver.agxPy in agxViewer
View source code
tutorial_direct_iterative_solver

Tutorial: Grasping hand

This script shows you how to set up a scene with accurate frictional contact simulation using the DIRECT solver

View source code:

Grasping hand

Tutorial: Using Virtual Inertia

This file demonstrates the functionality of the virtual inertia class that adds virtual inertia elements to a constraint that will add extra resistance to translational and rotational movements in the general constraint axis. This can be used to emulate mechanisms modeled with constraints that have internal inertia

Start tutorial_virtualInertia.agxPy in agxViewer
View source code
tutorial_virtualInertia

Tutorial: Using AMOR (Automatic MOdel Reduction) for speeding up simulation

This demonstrates how to use MergedBody and MergeSplitHandler to automatically simplify a scene to achieve speedup.

Start tutorial_mergedBody1.agxPy in agxViewer
View source code
tutorial_mergedBody1

Tutorial: Improve performance in a dynamic scene with many bodies

This scene demonstrates how AMOR can speed up simulation in a scene where many bodies are created in a dynamic scene with a spinning "table".

Start tutorial_AMOR.agxPy in agxViewer
View source code
tutorial_AMOR

Tutorial: Using agxModel::Track to model a tracked vehicle

Required licenses: agxTracks

This tutorial will show you how to use the agxModel::Track class to model a tracked vehicle/crawler.

Start tutorial_trackedVehicle.agxPy in agxViewer
View source code
tutorial_trackedVehicle

Tutorial: Combustion Engine

Required licenses: agxDriveTrain

This tutorial illustrates how to use the agxDriveTrain.CombustionEngine class for simulating an engine.. Start tutorial_driveTrain_combustionEngine.agxPy in agxViewer
View source code

tutorial_driveTrain_combustionEngine

Tutorial: Modelling a basic car with WheelJoint

This scripts demonstrates how to use the WheelJoint constraint for modelling the ackerman steering system including suspension.

Start tutorial_wheel_joint.agxPy in agxViewer
View source code
tutorial_wheel_joint

Tutorial: Demonstration of various steering models

This script demonstrates the different steering models available for a WheelJoint:

  • AckermannSteering
  • BellCrankSteering
  • ShortRackPinionSteering
  • DavisSteering
Start tutorial_carSteering.agxPy in agxViewer
View source code
tutorial_carSteering

Tutorial: Set robot pose

Required licenses: agxControl

Demonstrates how to initialize and set up a simulation using multiple Panda robots loaded from URDF. We compute and apply forward kinematics based on random joint configurations, ensuring valid poses by respecting joint limits.

Tutorial: Gravity Compensation

Required licenses: agxControl

Shows how to set up and perform gravity compensation with a Franka Emika Panda robot. We use inverse dynamics to calculate the torques needed at each joint to maintain the robot's position without acceleration, counteracting the effects of gravity. These torques are then applied to the robot's joints, ensuring it holds its pose.

Tutorial: Trajectory Tracking

Required licenses: agxControl

This tutorial demonstrates how to generate straight-line trajectories in joint and task space and track them using feed-forward torque control. We compute the torques using inverse dynamics to actuate the Panda robot.

Tutorial: Differential Kinematics

Required licenses: agxControl

Demonstrates how to track a moving target using position-based servoing. Postion-based servoing computes the tracking error between the end-effector's and object's pose. It then uses differential kinematics to compute the manipulator Jacobian and solves for the desired joint velocities. These joint velocities are input to the actuators of the Panda robot.

Tutorial: Computed Torque Control

Required licenses: agxControl

This script shows how to implement computed torque control, or the inverse dynamics controller, to track a trajectory. Along the trajectory, we unexpectedly let the robot collide with an object, causing it to diverge from the intended path. However, since computed torque control relies on feedback, it recovers gracefully.

Tutorial: Pick-and-Place

Required licenses: agxControl

This tutorial shows how to control a Panda robot to pick up boxes through frictional contacts and stack them. We use two controllers to manage the robot's motion. A high-level controller handles tasks related to the gripper and determines the robot's desired trajectory. A low-level controller tracks the target joint angles provided by the high-level controller and uses a force/torque sensor to estimate the load on the tool when moving different objects.

Tutorial: Controlled Robot using electric motor model

This script demonstrates how to model electric motors for a controlled robot.

Robot tutorial

Tutorial: Modelling a Robot and controlling it using a PID controller

Required licenses: agxDriveTrain

This tutorial demonstrates how a robot can be modelled from individual parts. It also show how an ordinary PID controller can be used to control the movements of the robot to follow a predefined trajectory read from a file. PID controller chapter in the User manual goes through this example in more detail

Start tutorial_robot_pid_control.agxPy in agxViewer
View source code

Tutorial: Simulating a robot suction gripper

This tutorial demonstrates how to model a custom suction gripper using the

agxModel::SuctionGripper
class.

Start tutorial_custom_suction_gripper.agxPy in agxViewer
View source code
tutorial_custom_suction_gripper.agxPy

Tutorial: Modelling a gripping mechanism

This tutorial illustrates how to model a gripping device. To be able to pick up an object using only friction, you will need to consider the material/solve model for the contacts between the gripper and the lifted object

Start tutorial_gripper.agxPy in agxViewer
View source code
tutorial_gripper

Tutorial: Simulating Trees

This tutorial will demonstrate how to use the agxModel::Tree class to simulate a flexible tree structures with stem and branches. The trees can be broken into parts because of collisions or forces.

Start tutorial_tree.agxPy in agxViewer
View source code
tutorial_tree

Tutorial: Render the scene to an image

This script demonstrates how to render color and depth buffer to image If matplotlib is present it shows the buffers in a figure.

Start tutorial_renderToImage.agxPy in agxViewer
View source code
tutorial_renderToImage

Tutorial: Lidar

This script shows how to create a Lidar sensor and read back data (point cloud) from it. The Lidar uses GPU accelerated ray tracing.

Note: The Lidar simulation requires a graphics card that supports CUDA.

Start tutorial_lidar.agxPy in agxViewer
View source code
tutorial_lidar

Tutorial: Lidar and Camera sensors

This script shows how to create an image based Lidar sensor together with depth and color cameras attached to a moving body. Note that this tutorial does not use the now recommended Lidar sensor, part of the agxSensor library which uses GPU accelerated ray tracing. See tutorial "Lidar" above for details of that Lidar sensor.

Start tutorial_lidar_and_camera_sensors.agxPy in agxViewer
View source code
tutorial_lidar_and_camera_sensors

Tutorial: Mesh reduction

This tutorial demonstrates how to use the

agxUtil.reduceMesh()
function for reduction of triangle meshes.

Start tutorial_reduce_mesh.agxPy in agxViewer
View source code
tutorial_reduce_mesh.agxPy

Tutorial: Polyhedra generation

This tutorial demonstrates how to use the

agxUtil.PrimitiveMeshGenerator.generateVoronoiPolyhedraMesh
to generate a polyhedra mesh from a randomly generated Voronoi Diagram.

Start tutorial_polyhedra_generation.agxPy in agxViewer
View source code
tutorial_polyhedra_generation.agxPy

Tutorial: Closest shape distance

This tutorial show how you can use the

agxCollide.computeShapeDistance
function to calculate the shortest distance between convex shapes.

Start tutorial_shape_distance.agxPy in agxViewer
View source code
tutorial_shape_distance.agxPy

Tutorial: Creating oriented volumes

This tutorial show how you can use the

agxUtil.createOrientedBox, agxUtil.createOrientedCylinder
and
agxUtil.createOrientedCapsule
to compute oriented bounding volumes based on a set of vertices.

Start tutorial_create_bounding_volume.agxPy in agxViewer
View source code
tutorial_create_bounding_volume.agxPy

Tutorial: Simulating a Beam

This tutorial shows how to use the agxModel::Beam class.

Start tutorial__beam.agxPy in agxViewer
View source code
tutorial_beam.agxPy

Tutorial: Simulating a robot suction gripper

This tutorial demonstrates how to model a custom suction gripper using the

agxModel::SuctionGripper
class.

Start tutorial_custom_suction_gripper.agxPy in agxViewer
View source code
tutorial_custom_suction_gripper.agxPy

Tutorial: Material library

This script demonstrates how to use predefined materials from the Material Library for various objects.

Start tutorial_material_library.agxPy in agxViewer
View source code
tutorial_material_library

Tutorial: Per contact point friction

This script demonstrates how a per contact point friction model can be setup using ContactEventListener. A texture is used as a lookup table for getting non-homogeneous friction over the surface of a box. The lookup into the friction texture is based on projection down to the x/y plane.

Start tutorial_per_contact_point_friction.agxPy in agxViewer
View source code

Tutorial: Friction

This demonstrates basic friction modeling. The angle of the plane can be altered using left/right key. Friction coefficient can be altered using up/down key.

Start tutorial_friction.agxPy in agxViewer
View source code

Tutorial: BallJoint Secondary Constraints

This script demonstrates the basics of how to set up and use the secondary constraints of a ball joint, specifically cone limit, twist range and friction controller constraints.

Start tutorial_balljoint_secondary_constraints.agxPy in agxViewer
View source code

Tutorial: Gamepad

This script demonstrates how to use the Python API for accessing joystick/gamepad in a simulation.

Start tutorial_gamepad.agxPy in agxViewer
View source code

Tutorial: Recompute texture coordinates for a mesh model.

This example demonstrates a tool that will recompute texture coordinates from a texture atlas.

tutorial_recomputeTextureCoordinates

Tutorial: Center of buoyancy

This script demonstrates the basics of enabling and accessing the position of center of buoyancy in a hydrodynamics scene.

Start tutorial_centerOfBuoyancy.agxPy in agxViewer
View source code

Tutorial: ObserverFrame

ObserverFrame can be used to measure data for a rigid body including, position, velocity and acceleration.

Start tutorial_observerFrame.agxPy in agxViewer
View source code

Tutorial: agxPlot

agxPlot is an API (available in Python, C++, C#) for easy plotting of data. It uses a WebAPI for the actual plotting.

Start tutorial_agxPlot.agxPy in agxViewer
View source code

Tutorial: Change machine pose - ReconfigureRequest

The reconfigure request is a utility class in agxUtil with functionality to compute new transforms for a collection of bodies given a set of values for constraint angles.

This tutorial shows how it can be used to change the pose of a wheel loader, an excavator as well as a robot.

The tutorial also shows extra handling which can be needed after updating many body transforms to maintain the simulation in a good state.

Start tutorial_machine_reconfiguration.agxPy in agxViewer
View source code