Pendulum 1-2 Robot Model

This sample project includes a model of a underactuated robot structured as a double pendulum with two distal links. The proximal link is actuated with a torque motor, and the distal links use passive pivots with only friction.

This model is demonstrated in the pendulum-1-2-demo.wbt world.

../_images/pendulum-1-2-sim.png

Screenshot of Webots model of 1-2 pendulum with a driven base joint and two passive distal joints. The robot is shown in the neutral pose.

System Kinematics

The bodies are as follows:

name

color

notes

base

blue

massive base resting on ground

link1

red

pivoting arm, with center of mass offset above the joint axis

link2A

green

upper passively pivoting arm,

link2B

green

lower passively pivoting arm, somewhat shorter than link2A

The joints are as follows:

name

parent

child

notes

joint1

base

link1

includes motor1 and the joint1 sensor

joint2A

link1

link2A

includes joint2A position sensor

joint2B

link1

link2A

includes joint2B position sensor

The axes are as follows:

name

direction

notes

joint1

along X

located 1.0 meters above the ground plane

joint2A

along X

located 0.5 meters about the joint1 axis

joint2B

along X

located 0.3 meters below the joint1 axis

Design Notes

  1. The robot is directly modeled in the scene tree so all parameters can be visible. In general it is more flexible to transfer models to .proto files so they can be instantiated more than once.

  2. For simplicity, the model uses only primitive shapes (boxes). The same shapes are used for both rendering and contact detection (i.e. bounding objects). This also allows the simulator to automatically calculate inertia properties.

  3. Each Solid node uses the translation vector to place the link body coordinate origin at a logical point on the joint axis. This convention is intended to keep the hinge vectors more legible.

  4. Each Shape node has been wrapped in a Transform node to ease positioning it with the link body coordinates.

  5. The sample controller runs an event loop which calculates joint1 torques based on elapsed time. It could be extended to use joint position data for feedback.

CAD Drawings

The following images were generated using a Fusion 360 CAD model independently drawn to the same dimensions as the Webots robot model.

../_images/pendulum-1-2-CAD-v3-dims.png

Dimensioned sketch of CAD model of 1-2 pendulum, front view, showing all X-Z dimensions.

../_images/pendulum-1-2-CAD-v3-oblique.png

CAD model of 1-2 pendulum.

../_images/pendulum-1-2-CAD-v3-front-right.png

CAD model of 1-2 pendulum, front and right views.

Sample Robot Control Code

 1# pendulum_1_2.py
 2#
 3# Sample Webots controller file for driving the
 4# underactuated 1-2 pendulum.  The robot has a driven
 5# base joint between the base and link1, and passive
 6# joints between link1 and the two distal links link2A
 7# and link2B.
 8#
 9# No copyright, 2020-2021, Garth Zeglin.  This file is
10# explicitly placed in the public domain.
11
12print("loading pendulum_1_2.py...")
13
14# Import the Webots simulator API.
15from controller import Robot
16
17# Import the standard Python math library.
18import math
19
20print("pendulum_1_2.py waking up...")
21
22# Define the time step in milliseconds between
23# controller updates.
24EVENT_LOOP_DT = 20
25
26# Request a proxy object representing the robot to
27# control.
28robot = Robot()
29
30# Fetch handles for the joint sensors.
31j1  = robot.getDevice('joint1')
32j2A = robot.getDevice('joint2A')
33j2B = robot.getDevice('joint2B')
34
35# Specify the sampling rate for the joint sensors.
36j1.enable(EVENT_LOOP_DT)
37j2A.enable(EVENT_LOOP_DT)
38j2B.enable(EVENT_LOOP_DT)
39
40# Fetch handle for the 'base' joint motor.  In this
41# example the motor will be controlled as a torque
42# motor, bypassing the lower-level PID control.
43motor1 = robot.getDevice('motor1')
44motor1.setTorque(0.0)
45
46# Run an event loop until the simulation quits,
47# indicated by the step function returning -1.
48while robot.step(EVENT_LOOP_DT) != -1:
49
50    # Read simulator clock time.
51    t = robot.getTime()
52
53    # Read the new joint positions.
54    q1  = j1.getValue()
55    q2A = j2A.getValue()
56    q2B = j2B.getValue()
57
58    # Compute and apply new base joint actuator torque.
59    # In this example, the excitation is only based on
60    # time, but could also be a function of the joint
61    # positions.
62    tau = 3 * math.sin(3*t)
63    motor1.setTorque(tau)

World File

  1#VRML_SIM R2022a utf8
  2WorldInfo {
  3}
  4Viewpoint {
  5  orientation 0.20637375705407857 0.11296232240268078 -0.9719307517085652 2.083640805255243
  6  position 1.7870404774717816 3.2844836209794273 2.3418665277932647
  7}
  8Background {
  9  skyColor [
 10    0.1 0.1 0.1
 11  ]
 12}
 13DirectionalLight {
 14  direction 0.4 -0.5 -1
 15  intensity 3
 16  castShadows TRUE
 17}
 18RectangleArena {
 19  rotation 1.8366025517039032e-06 -1.836602551703903e-06 0.9999999999966269 1.5707963267982696
 20  floorSize 2 2
 21}
 22Robot {
 23  rotation 0 0 1 1.5708
 24  children [
 25    DEF baseObject Transform {
 26      translation 0 0 0.6
 27      children [
 28        Shape {
 29          appearance PaintedWood {
 30            colorOverride 0.21529 0.543008 0.99855
 31          }
 32          geometry Box {
 33            size 0.3 0.5 1.2
 34          }
 35        }
 36      ]
 37    }
 38    HingeJoint {
 39      jointParameters HingeJointParameters {
 40        anchor 0 0 1
 41      }
 42      device [
 43        PositionSensor {
 44          name "joint1"
 45        }
 46        RotationalMotor {
 47          name "motor1"
 48          acceleration 2
 49          maxVelocity 3.14
 50          minPosition -10
 51          maxPosition 10
 52          maxTorque 20
 53        }
 54      ]
 55      endPoint Solid {
 56        translation 0.15 0 1
 57        rotation 1 0 0 0
 58        children [
 59          DEF link1Shape Transform {
 60            translation 0.08 0 0.1
 61            children [
 62              Shape {
 63                appearance PaintedWood {
 64                  colorOverride 0.990494 0.516915 0.468254
 65                }
 66                geometry Box {
 67                  size 0.1 0.3 1
 68                }
 69              }
 70            ]
 71          }
 72          HingeJoint {
 73            jointParameters HingeJointParameters {
 74              anchor 0 0 0.5
 75              dampingConstant 0.1
 76            }
 77            device [
 78              PositionSensor {
 79                name "joint2A"
 80              }
 81            ]
 82            endPoint Solid {
 83              translation 0.13 0 0.5
 84              rotation 1 0 0 0
 85              children [
 86                DEF link2AShape Transform {
 87                  translation 0.07 0 0.2
 88                  children [
 89                    Shape {
 90                      appearance PaintedWood {
 91                        colorOverride 0.413001 1 0.33489
 92                      }
 93                      geometry Box {
 94                        size 0.1 0.1 0.6
 95                      }
 96                    }
 97                  ]
 98                }
 99              ]
100              name "link2A"
101              boundingObject USE link2AShape
102              physics Physics {
103                density -1
104                mass 0.5
105              }
106            }
107          }
108          HingeJoint {
109            jointParameters HingeJointParameters {
110              anchor 0 0 -0.3
111              dampingConstant 0.1
112            }
113            device [
114              PositionSensor {
115                name "joint2B"
116              }
117            ]
118            endPoint Solid {
119              translation 0.13 0 -0.3
120              rotation 1 0 0 0
121              children [
122                DEF link2BShape Transform {
123                  translation 0.07 0 -0.15
124                  children [
125                    Shape {
126                      appearance PaintedWood {
127                        colorOverride 0.413001 1 0.33489
128                      }
129                      geometry Box {
130                        size 0.1 0.1 0.4
131                      }
132                    }
133                  ]
134                }
135              ]
136              name "link2B"
137              boundingObject USE link2BShape
138              physics Physics {
139                density -1
140                mass 0.5
141              }
142            }
143          }
144        ]
145        name "link1"
146        boundingObject USE link1Shape
147        physics Physics {
148          density -1
149          mass 0.5
150        }
151      }
152    }
153  ]
154  name "pendulum_1_2"
155  boundingObject USE baseObject
156  physics Physics {
157    density -1
158    mass 20
159  }
160  controller "pendulum_1_2"
161}