Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components

Library of components of the robot

Information

This library contains the different components of the r3 robot. Usually, there is no need to use this library directly.

Extends from Modelica.Icons.Package (Icon for standard packages).

Package Content

Name Description
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisControlBus AxisControlBus Data bus for one robot axis
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.ControlBus ControlBus Data bus for all axes of robot
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathPlanning1 PathPlanning1 Generate reference angles for fastest kinematic movement
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathPlanning6 PathPlanning6 Generate reference angles for fastest kinematic movement
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathToAxisControlBus PathToAxisControlBus Map path planning to one axis control bus
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.GearType1 GearType1 Motor inertia and gearbox model for r3 joints 1,2,3
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.GearType2 GearType2 Motor inertia and gearbox model for r3 joints 4,5,6
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.Motor Motor Motor model including current controller of r3 motors
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.Controller Controller P-PI cascade controller for one axis
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisType1 AxisType1 Axis model of the r3 joints 1,2,3
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisType2 AxisType2 Axis model of the r3 joints 4,5,6
Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.MechanicalStructure MechanicalStructure Model of the mechanical part of the r3 robot (without animation)

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisControlBus Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisControlBus

Data bus for one robot axis

Information

Signal bus that is used to communicate all signals for one axis. This is an expandable connector which has a "default" set of signals. Note, the input/output causalities of the signals are determined from the connections to this bus.

Extends from Modelica.Icons.SignalSubBus (Icon for signal sub-bus).

Contents

NameDescription
motion_ref= true, if reference motion is not in rest
angle_refReference angle of axis flange [rad]
angleAngle of axis flange [rad]
speed_refReference speed of axis flange [rad/s]
speedSpeed of axis flange [rad/s]
acceleration_refReference acceleration of axis flange [rad/s2]
accelerationAcceleration of axis flange [rad/s2]
current_refReference current of motor [A]
currentCurrent of motor [A]
motorAngleAngle of motor flange [rad]
motorSpeedSpeed of motor flange [rad/s]

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.ControlBus Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.ControlBus

Data bus for all axes of robot

Information

Signal bus that is used to communicate all signals of the robot. This is an expandable connector which has a "default" set of signals. Note, the input/output causalities of the signals are determined from the connections to this bus.

Extends from Modelica.Icons.SignalBus (Icon for signal bus).

Contents

NameDescription
axisControlBus1Bus of axis 1
axisControlBus2Bus of axis 2
axisControlBus3Bus of axis 3
axisControlBus4Bus of axis 4
axisControlBus5Bus of axis 5
axisControlBus6Bus of axis 6

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathPlanning1 Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathPlanning1

Generate reference angles for fastest kinematic movement

Information

Given

this component computes the fastest movement under the given constraints. This means, that:

  1. The axis accelerates with the maximum acceleration until the maximum speed is reached.
  2. Drives with the maximum speed as long as possible.
  3. Decelerates with the negative of the maximum acceleration until rest.

The acceleration, constant velocity and deceleration phase are determined in such a way that the movement starts form the start angles and ends at the end angles. The output of this block are the computed angles, angular velocities and angular acceleration and this information is stored as reference motion on the controlBus of the r3 robot.

Extends from Blocks.Icons.Block (Basic graphical layout of input/output block).

Parameters

NameDescription
angleBegDegStart angle [deg]
angleEndDegEnd angle [deg]
speedMaxMaximum axis speed [rad/s]
accMaxMaximum axis acceleration [rad/s2]
startTimeStart time of movement [s]
swingTimeAdditional time after reference motion is in rest before simulation is stopped [s]

Connectors

NameDescription
controlBus 

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathPlanning6 Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathPlanning6

Generate reference angles for fastest kinematic movement

Information

Given

this component computes the fastest movement under the given constraints. This means, that:

  1. Every axis accelerates with the maximum acceleration until the maximum speed is reached.
  2. Drives with the maximum speed as long as possible.
  3. Decelerates with the negative of the maximum acceleration until rest.

The acceleration, constant velocity and deceleration phase are determined in such a way that the movement starts form the start angles and ends at the end angles. The output of this block are the computed angles, angular velocities and angular acceleration and this information is stored as reference motion on the controlBus of the r3 robot.

Extends from Blocks.Icons.Block (Basic graphical layout of input/output block).

Parameters

NameDescription
naxisNumber of driven axis
angleBegDeg[naxis]Start angles [deg]
angleEndDeg[naxis]End angles [deg]
speedMax[naxis]Maximum axis speed [rad/s]
accMax[naxis]Maximum axis acceleration [rad/s2]
startTimeStart time of movement [s]
swingTimeAdditional time after reference motion is in rest before simulation is stopped [s]

Connectors

NameDescription
controlBus 

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathToAxisControlBus Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.PathToAxisControlBus

Map path planning to one axis control bus

Information

This model stores the 4 reference variables q, qd, qdd, moving from the path planning on the axis control bus.

Extends from Modelica.Blocks.Icons.Block (Basic graphical layout of input/output block).

Parameters

NameDescription
nAxisNumber of driven axis
axisUsedMap path planning of axisUsed to axisControlBus

Connectors

NameDescription
q[nAxis] 
qd[nAxis] 
qdd[nAxis] 
axisControlBus 
moving[nAxis] 

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.GearType1 Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.GearType1

Motor inertia and gearbox model for r3 joints 1,2,3

Information

Models the gearbox used in the first three joints with all its effects, like elasticity and friction. Coulomb friction is approximated by a friction element acting at the "motor"-side. In reality, bearing friction should be also incorporated at the driven side of the gearbox. However, this would require considerable more effort for the measurement of the friction parameters. Default values for all parameters are given for joint 1. Model relativeStates is used to define the relative angle and relative angular velocity across the spring (=gear elasticity) as state variables. The reason is, that a default initial value of zero of these states makes always sense. If the absolute angle and the absolute angular velocity of model Jmotor would be used as states, and the load angle (= joint angle of robot) is NOT zero, one has always to ensure that the initial values of the motor angle and of the joint angle are modified correspondingly. Otherwise, the spring has an unrealistic deflection at initial time. Since relative quantities are used as state variables, this simplifies the definition of initial values considerably.

Extends from Modelica.Mechanics.Rotational.Icons.Gearbox (Icon of a gear box), Modelica.Mechanics.Rotational.Interfaces.PartialTwoFlanges (Partial model for a component with two rotational 1-dim. shaft flanges).

Parameters

NameDescription
iGear ratio
cSpring constant [N.m/rad]
dDamper constant [N.m.s/rad]
Rv0Viscous friction torque at zero velocity [N.m]
Rv1Viscous friction coefficient (R=Rv0+Rv1*abs(qd)) [N.m.s/rad]
peakMaximum static friction torque is peak*Rv0 (peak >= 1)

Connectors

NameDescription
flange_aFlange of left shaft
flange_bFlange of right shaft

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.GearType2 Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.GearType2

Motor inertia and gearbox model for r3 joints 4,5,6

Information

The elasticity and damping in the gearboxes of the outermost three joints of the robot is neglected. Default values for all parameters are given for joint 4.

Extends from Modelica.Mechanics.Rotational.Icons.Gearbox (Icon of a gear box), Modelica.Mechanics.Rotational.Interfaces.PartialTwoFlanges (Partial model for a component with two rotational 1-dim. shaft flanges).

Parameters

NameDescription
iGear ratio
Rv0Viscous friction torque at zero velocity [N.m]
Rv1Viscous friction coefficient in [Nms/rad] (R=Rv0+Rv1*abs(qd))
peakMaximum static friction torque is peak*Rv0 (peak >= 1)

Connectors

NameDescription
flange_aFlange of left shaft
flange_bFlange of right shaft

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.Motor Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.Motor

Motor model including current controller of r3 motors

Information

Default values are given for the motor of joint 1. The input of the motor is the desired current (the actual current is proportional to the torque produced by the motor).

Extends from Electrical.Machines.Icons.Machine (Generic icon of an electric machine).

Parameters

NameDescription
JMoment of inertia of motor [kg.m2]
kGain of motor
wTime constant of motor
DDamping constant of motor
w_maxMaximum speed of motor [rad/s]
i_maxMaximum current of motor [A]

Connectors

NameDescription
flange_motor 
axisControlBus 

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.Controller Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.Controller

P-PI cascade controller for one axis

Information

This controller has an inner PI-controller to control the motor speed, and an outer P-controller to control the motor position of one axis. The reference signals are with respect to the gear-output, and the gear ratio is used in the controller to determine the motor reference signals. All signals are communicated via the "axisControlBus".

Extends from Blocks.Icons.Block (Basic graphical layout of input/output block).

Parameters

NameDescription
kpGain of position controller
ksGain of speed controller
TsTime constant of integrator of speed controller [s]
ratioGear ratio of gearbox

Connectors

NameDescription
axisControlBus 

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisType1 Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisType1

Axis model of the r3 joints 1,2,3

Information

Model of axis 1, 2, 3 of the robot r3. An axis consists of a gearbox with modelled gear elasticity and bearing friction, a model of the electrical motor and a continuous-time cascade controller.

Extends from AxisType2 (Axis model of the r3 joints 4,5,6).

Parameters

NameDescription
Controller
kpGain of position controller
ksGain of speed controller
TsTime constant of integrator of speed controller [s]
Motor
kGain of motor
wTime constant of motor
DDamping constant of motor
JMoment of inertia of motor [kg.m2]
Gear
ratioGear ratio
Rv0Viscous friction torque at zero velocity in [Nm] [N.m]
Rv1Viscous friction coefficient in [Nms/rad] [N.m.s/rad]
peakMaximum static friction torque is peak*Rv0 (peak >= 1)
cSpring constant [N.m/rad]
cdDamper constant [N.m.s/rad]

Connectors

NameDescription
flange 
axisControlBus 

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisType2 Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.AxisType2

Axis model of the r3 joints 4,5,6

Information

The axis model consists of the controller, the motor including current controller and the gearbox including gear elasticity and bearing friction. The only difference to the axis model of joints 4,5,6 (= model axisType2) is that elasticity and damping in the gear boxes are not neglected.

The input signals of this component are the desired angle and desired angular velocity of the joint. The reference signals have to be "smooth" (position has to be differentiable at least 2 times). Otherwise, the gear elasticity leads to significant oscillations.

Default values of the parameters are given for the axis of joint 1.

Parameters

NameDescription
gear 
Controller
kpGain of position controller
ksGain of speed controller
TsTime constant of integrator of speed controller [s]
Motor
kGain of motor
wTime constant of motor
DDamping constant of motor
JMoment of inertia of motor [kg.m2]
Gear
ratioGear ratio
Rv0Viscous friction torque at zero velocity in [Nm] [N.m]
Rv1Viscous friction coefficient in [Nms/rad] [N.m.s/rad]
peakMaximum static friction torque is peak*Rv0 (peak >= 1)

Connectors

NameDescription
flange 
axisControlBus 

Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.MechanicalStructure Modelica.Mechanics.MultiBody.Examples.Systems.RobotR3.Components.MechanicalStructure

Model of the mechanical part of the r3 robot (without animation)

Information

This model contains the mechanical components of the r3 robot (multibody system).

Parameters

NameDescription
animation= true, if animation shall be enabled
mLoadMass of load [kg]
rLoad[3]Distance from last flange to load mass> [m]
gGravity acceleration [m/s2]

Connectors

NameDescription
axis1 
axis2 
axis3 
axis4 
axis5 
axis6 
Automatically generated Thu Dec 19 17:20:06 2019.