Readonly monitorReadonly pubEmits true only when the client transitions into the ready state,
meaning both sockets have become opened.
distinctUntilChanged() guarantees that repeated true values are suppressed.
However, new subscribers will still immediately receive the last replayed true
if the client is already ready.
Readonly reqReadonly requestEmits true when both req/res and pub/sub sockets are opened. Emits false if any socket closes. This is a hot observable and always replays the latest opened state on subscription.
Private Optional systemCreates and returns and instance of DataMonitoring class.
Optional config: MonitoringConfigReturns an Observable that emits once when both req/res and pub/sub sockets are opened, then completes.
Observable
The maximum time (in milliseconds) to wait for both sockets to open. Default is 5000 ms.
Executes the homing procedure to locate the home position value (0x2005:01).
You can optionally provide a configuration object that specifies acceleration, method, and speeds; if not provided, the parameter values already set on the device will be used.
The function will first emit a "running" status, followed by either "succeeded" or "failed". After completion, the device will remain in the Operation Enabled state.
No CiA402 state transitions will occur for the "Homing on current position" methods (35 and 37). Additionally, the halt bit will remain unchanged for these methods, in contrast to other methods where the halt bit is cleared.
An Observable that emits the status of the homing procedure.
Reference to the device being homed.
Optional config: HomingProcedureConfigOptional configuration for the homing procedure.
Interval for monitoring the homing procedure status in microseconds (default: 50,000 μs).
Timeout for the homing request in milliseconds (default: 300,000 ms).
Executes a position profile on the specified device.
Downloads target position, velocity, acceleration and deceleration first, then sets Profile Position Mode, transitions to Operation Enabled and applies the set point. The brake is released automatically by the drive in PP mode. What happens next depends on the combination of skipQuickStop and targetReachTimeout:
skipQuickStop: false (default) + targetReachTimeout set: Waits for the target reached bit (0x6041) within the given timeout, waits for holdingDuration if set, then issues a quick stop. The state waited for after the quick stop depends on the quick stop option code (0x605A): Quick Stop Active if the code is 6, Switch On Disabled otherwise. Throws if the target is not reached in time.
skipQuickStop: false (default) + no positive targetReachTimeout: Throws immediately — the function cannot determine when to issue the quick stop.
skipQuickStop: true + targetReachTimeout set: Waits for the target reached bit within the given timeout but does not issue a quick stop. The device remains in the Operation Enabled state.
skipQuickStop: true + no targetReachTimeout: Returns immediately after applying the set point. The device remains in the Operation Enabled state.
When skipQuickStop is true and an error is thrown (e.g. target not reached in time), the drive remains in Operation Enabled. The caller is responsible for issuing a quick stop or transitioning the drive to a safe state.
Error if skipQuickStop is false and targetReachTimeout is not a positive number.
Error if the target is not reached within targetReachTimeout.
Reference to the target device.
Position profile configuration.
Executes a torque profile on the specified device.
Downloads target torque and slope first, then sets Torque Profile Mode and transitions to Operation Enabled. The brake is released automatically by the drive in PT mode. What happens next depends on the combination of skipQuickStop and targetReachTimeout:
skipQuickStop: false (default) + targetReachTimeout set: Waits for the target reached bit (0x6041) within the given timeout, waits for holdingDuration if set, then issues a quick stop. The state waited for after the quick stop depends on the quick stop option code (0x605A): Quick Stop Active if the code is 6, Switch On Disabled otherwise. Throws if the target is not reached in time.
skipQuickStop: false (default) + no positive targetReachTimeout: Throws immediately — the function cannot determine when to issue the quick stop.
skipQuickStop: true + targetReachTimeout set: Waits for the target reached bit within the given timeout but does not issue a quick stop. The device remains in the Operation Enabled state.
skipQuickStop: true + no targetReachTimeout: Returns immediately after enabling the drive. The device remains in the Operation Enabled state.
When skipQuickStop is true and an error is thrown (e.g. target not reached in time), the drive remains in Operation Enabled. The caller is responsible for issuing a quick stop or transitioning the drive to a safe state.
Error if skipQuickStop is false and targetReachTimeout is not a positive number.
Error if the target is not reached within targetReachTimeout.
Reference to the target device.
Torque profile configuration.
Executes a velocity profile on the specified device.
Downloads target velocity, acceleration and deceleration first, then sets Profile Velocity Mode and transitions to Operation Enabled. The brake is released automatically by the drive in PV mode. What happens next depends on the combination of skipQuickStop and targetReachTimeout:
skipQuickStop: false (default) + targetReachTimeout set: Waits for the target reached bit (0x6041) within the given timeout, waits for holdingDuration if set, then issues a quick stop. The state waited for after the quick stop depends on the quick stop option code (0x605A): Quick Stop Active if the code is 6, Switch On Disabled otherwise. Throws if the target is not reached in time.
skipQuickStop: false (default) + no positive targetReachTimeout: Throws immediately — the function cannot determine when to issue the quick stop.
skipQuickStop: true + targetReachTimeout set: Waits for the target reached bit within the given timeout but does not issue a quick stop. The device remains in the Operation Enabled state.
skipQuickStop: true + no targetReachTimeout: Returns immediately after enabling the drive. The device remains in the Operation Enabled state.
When skipQuickStop is true and an error is thrown (e.g. target not reached in time), the drive remains in Operation Enabled. The caller is responsible for issuing a quick stop or transitioning the drive to a safe state.
Error if skipQuickStop is false and targetReachTimeout is not a positive number.
Error if the target is not reached within targetReachTimeout.
Reference to the target device.
Velocity profile configuration.
Start monitoring.
Note that the returned observable will never complete on its own.
If you unsubscribe from it, the teardown code will send a request to the master to stop the monitoring. That means you will end up with an observable that is not complete, but it won't emit any values. This is fine when you want to use the monitoring observable directly in the template with async pipe, which will unsubscribe automatically and stop the monitoring when you leave the component.
If you need to complete the observable so that, for example, the toArray() operator works as expected, then use the DataMonitoring class, which has a stop method. It can optionally buffer data for exporting as CSV or performing statistics on it.
An observable of an array of parameter values.
Device parameter IDs to monitor.
At what interval should the master application send values.
Optional config: MonitoringConfigConfigure the topic, buffer size, distinct.
How long will the client wait for the master to confirm that monitoring has started.
TODO: return device parameters instead of just parameters get parameters from ESI uprfront, and then when parameters are received from motion master just concatenate (spread operator) props from ESI and props from parameter assign device parameter id like 0x1018:00.12345 when assembling device parameter, get parameter from device in ESI based on product code, see ESI service this should probably done for other get parameters functions, get ESI file from device or prepared, get data from it
Optional config: MonitoringConfigOptional config: MonitoringConfigWaits until both req/res and pub/sub sockets are opened.
requestTimeout milliseconds for both sockets to open.Promise
Maximum time in milliseconds to wait for both sockets to open. Default is 5000 ms.
Generated using TypeDoc
Emits a single time when the client becomes ready for the first time.