Compatibility
This table specifies the compatibility of the Python package versions with the Vention's MachineMotion and Pendant versions.
Package | MachineMotion | Pendant |
---|---|---|
v1.12.x* | v2.13.x | v3.2, v3.3 |
v1.13.0 | >=v2.14.x | >=v3.4 |
v1.13.1 | >=v2.15.x | >=v3.5 |
v1.13.2 | >=v2.15.x | >=v3.5 |
v1.14.0 | >=v2.18.x | >=3.8 |
v2.0.0 | >=v3.0.0 | N/A** |
*Package versions before 1.13.0 were published to PyPi under the package name machine-code-python-sdk
**Post MMAI release (MachineMotion v3.0.0), machine-logic-sdk is no longer dependent on Pendant version.
Changelog
[2.0.0] - 2025-05-06
Added
New MotionProfile
class for defining Actuator
and ActuatorGroup
motion profiles (`move_absolute`, move_absolute_async
, move_relative
, move_relative_async
, move_continuous_asyc
). Import directly from machinelogic.
motion_profile.velocity
motion_profile.acceleration
motion_profile.jerk
Changed
Actuator
:new arguments for `actuator.move_absolute:`
(position: float, motion_profile: MotionProfile)
new arguments for `actuator.move_absolute_async:`
(position: float, motion_profile: MotionProfile)
new arguments for `actuator.move_relative:`
(position: float, motion_profile: MotionProfile)
new arguments for `actuator.move_relative_async:`
(position: float, motion_profile: MotionProfile)
new arguments for `actuator.move_continuous_async:`
(position: float, motion_profile: MotionProfile)
Removed
acceleration
argument fromactuator.stop()
method.
ActuatorGroup
:new arguments for `actuator_group.move_absolute:`
(position: float, motion_profile: MotionProfile)
new arguments for `actuator_group.move_absolute_async:`
(position: float, motion_profile: MotionProfile)
new arguments for `actuator_group.move_relative:`
(position: float, motion_profile: MotionProfile)
new arguments for `actuator_group.move_relative_async:`
(position: float, motion_profile: MotionProfile)
new arguments for `actuator_group.move_continuous_async:`
(position: float, motion_profile: MotionProfile)
Removed
acceleration
argument fromactuator_group.stop()
method.
DigitalInput
, `DigitalOutput`Pneumatic
andACMotor
classes:replaced
[class].configuration.device
with[class].configuration.device_id
replaced
[class].configuration.port
with[class].configuration.pin
added
[class].configuration.controller_port
Removed
removed
actuator.set_speed
(replaced with MotionProfile sent directly to move)removed
actuator.set_acceleration
(replaced with MotionProfile sent directly to move)removed
actuator.lock_brakes
methodremoved
actuator.unlock_brakes
methodremoved
actuator.state.brake
removed
actuator_group.set_speed
(replaced with MotionProfile sent directly to move)removed
actuator_group.set_acceleration
(replaced with MotionProfile sent directly to move)removed
actuator_group.lock_brakes
removed
actuator_group.unlock_brakes
Removed
BagGripper
as configurable item from machinelogicRemoved
BagGripper
ClassRemoved
Machine.get_bag_gripper
Removed
BagGripperConfiguration
Machine
A software representation of the entire Machine. A Machine is defined as any number of MachineMotions, each containing their own set of axes, outputs, inputs, pneumatics, and AC Motors. The Machine class offers a global way to retrieve these various components using the friendly names that you've defined in your MachineLogic configuration.
To create a new Machine with default settings, you can simply write:
machine = Machine()
If you need to connect to services running on a different machine or IP address, you can specify the IP address as follows:
machine = Machine("192.168.7.2")
You should only ever have a single instance of this object in your program.
state
Description The state of the Machine.
Type MachineState
get_ac_motor
Description Retrieves an AC Motor by name.
Parameters
name
Description The name of the AC Motor.
Type str
Returns
Description The AC Motor that was found.
Type ACMotor
Raises
Description If it is not found.
get_actuator
Description Retrieves an Actuator by name.
Parameters
name
Description The name of the Actuator.
Type str
Returns
Description The Actuator that was found.
Type Actuator
Raises
Type MachineException
Description If we cannot find the Actuator.
from machinelogic import Machine, MotionProfile
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
# Always home the actuator before starting to ensure position is properly calibrated.
my_actuator.home(timeout=10)
start_position = my_actuator.state.position
print("starting at position: ", start_position)
TARGET_DISTANCE = 150 # millimeters
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
my_actuator.move_relative(
distance=TARGET_DISTANCE,
motion_profile=new_motion_profile,
)
# first_move_end_position is approx. equal to start_position + target_distance.
first_move_end_position = my_actuator.state.position
print("first move finished at position: ", first_move_end_position)
# move back to starting position
TARGET_DISTANCE = -1 * TARGET_DISTANCE
my_actuator.move_relative(
distance=TARGET_DISTANCE,
motion_profile=new_motion_profile,
)
# approx. equal to start_position,
end_position = my_actuator.state.position
print("finished back at position: ", end_position)
get_input
Description Retrieves an DigitalInput by name.
Parameters
name
Description The name of the DigitalInput.
Type str
Returns
Description The DigitalInput that was found.
Type DigitalInput
Raises
Type MachineException
Description If we cannot find the DigitalInput.
from machinelogic import Machine
machine = Machine()
my_input = machine.get_input("Input")
if my_input.state.value:
print(f"{my_input.configuration.name} is HIGH")
else:
print(f"{my_input.configuration.name} is LOW")
get_machine_motion
Description Retrieves an IMachineMotion instance by name.
Parameters
name
Description The name of the MachineMotion.
Type str
Returns
Description The MachineMotion that was found.
Type MachineMotion
Raises
Type MachineException
Description If we cannot find the MachineMotion.
from machinelogic import Machine, MachineException
machine = Machine()
my_controller_1 = machine.get_machine_motion("Controller 1")
configuration = my_controller_1.configuration
print("Name:", configuration.name)
get_output
Description Retrieves an Output by name.
Parameters
name
Description The name of the Output
Type str
Returns
Description The Output that was found.
Type IOutput
Raises
Type MachineException
Description If we cannot find the Output.
from machinelogic import Machine, MachineException, DigitalOutputException
machine = Machine()
my_output = machine.get_output("Output")
my_output.write(True) # Write "true" to the Output
my_output.write(False) # Write "false" to the Output
get_pneumatic
Description Retrieves a Pneumatic by name.
Parameters
name
Description The name of the Pneumatic.
Type str
Returns
Description The Pneumatic that was found.
Type Pneumatic
Raises
Type MachineException
Description If we cannot find the Pneumatic.
import time
from machinelogic import Machine
machine = Machine()
my_pneumatic = machine.get_pneumatic("Pneumatic")
# Idle
my_pneumatic.idle_async()
time.sleep(1)
# Push
my_pneumatic.push_async()
time.sleep(1)
# Pull
my_pneumatic.pull_async()
time.sleep(1)
get_robot
Description Retrieves a Robot by name. If no name is specified, then returns the first Robot.
Parameters
name
Description The Robot name. If it's `None`, then the first Robot in the Robot list is returned.
Type str
Returns
Description The Robot that was found.
Type Robot
Raises
Type MachineException
Description If the Robot is not found.
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# Example of use: moving robot to specified joint angles in deg
my_robot.movej([0, -90, 120, -90, -90, 0])
get_scene
Description Returns the scene instance
Returns
Description The instance of the scene containing the scene assets.
Type Scene
Raises
Type MachineException
Description If failed to find the scene
on_mqtt_event
Description Attach a callback function to an MQTT topic.
Parameters
topic
Description The topic to listen on.
Type str
callback
Description A callback where the first argument is the topic and the second is the message.
Type Union[Callable[[str, str], None], None]
import time
from machinelogic import Machine
machine = Machine()
my_event_topic = "my_custom/event/topic"
# A "callback" function called everytime a new mqtt event on my_event_topic is received.
def event_callback(topic: str, message: str):
print("new mqtt event:", topic, message)
machine.on_mqtt_event(my_event_topic, event_callback)
machine.publish_mqtt_event(my_event_topic, "my message")
time.sleep(2)
machine.on_mqtt_event(my_event_topic, None) # remove the callback.
on_system_state_change
Description Adds a change listener to execute when the Machine state changes.
Parameters
callback
Description The callback
Type Callable[[MachineOperationalState, MachineSafetyState], None]
from machinelogic import Machine
machine = Machine()
# Callback function called everytime a new system state is received.
def on_machine_state_change_callback(operational_state, safety_state):
print('New Machine Operational State', operational_state)
print('New Machine Safety State', safety_state)
# To set an on_system_state_change callback
machine.on_system_state_change(on_machine_state_change_callback)
# To remove the callback
machine.on_system_state_change(None)
publish_mqtt_event
Description Publish an MQTT event.
Parameters
topic
Description Topic to publish.
Type str
message
Description Optional message. Defaults to None.
Type Optional[str]
import time
import json
from machinelogic import Machine
machine = Machine()
# Example for publishing a cycle-start and cycle-end topic and message
# to track application cycles in MachineAnalytics
cycle_start_topic = "application/cycle-start"
cycle_end_topic = "application/cycle-end"
cycle_message = {
"applicationId":"My Python Application",
"cycleId":"default"
}
json_cycle_message = json.dumps(cycle_message)
while True:
machine.publish_mqtt_event(cycle_start_topic, json_cycle_message)
print("Cycle Start")
time.sleep(5)
machine.publish_mqtt_event(cycle_end_topic, json_cycle_message)
time.sleep(1)
print("Cycle end")
reset
Description Reset the machine by trying to clear drive errors.
Returns
Description True if the machine was reset successfully, False otherwise.
Type bool
from machinelogic import Machine
machine = Machine()
# Example for resetting the machine if the MachineOperationalState is
# NON_OPERATIONAL. The reset programmatically tries to clear drive errors
if machine.state.operational_state == "NON_OPERATIONAL":
machine.reset()
print("Machine Reset")
MachineState
A representation of the state of the Machine.
operational_state
Description The operational state of the Machine.
safety_state
Description The safety state of the Machine.
Type MachineSafetyState
MachineOperationalState
Description: The machine's operational state.
NON_OPERATIONAL= 0
NORMAL= 1
MachineSafetyState
Description: The machine's safety state.
ERROR= -1
NONE= 0
EMERGENCY_STOP= 1
NORMAL= 2
MachineMotion
A software representation of a MachineMotion controller. The MachineMotion is comprised of many actuators, inputs, outputs, pneumatics, and ac motors. It keeps a persistent connection to MQTT as well.
You should NEVER construct this object yourself. Instead, it is best to rely on the Machine instance to provide you with a list of the available MachineMotions.
configuration
Description MachineMotionConfiguration: The representation of the configuration associated with this MachineMotion.
Type MachineMotionConfiguration
Actuator
A software representation of an Actuator. An Actuator is defined as a motorized axis that can move by discrete distances. It is not recommended that you construct this object yourself. Rather, you should query it from a Machine instance:
E.g.:
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
In this example, "New actuator" is the friendly name assigned to the Actuator in the MachineLogic configuration page.
configuration
Description The representation of the configuration associated with this MachineMotion.
state
Description The representation of the current state of this MachineMotion.
Type ActuatorState
home
Description Home the Actuator synchronously.
Parameters
timeout
Description The timeout in seconds.
Type float
Raises
Type ActuatorException
Description If the home was unsuccessful or request timed out.
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
my_actuator.home(timeout=10)
move_absolute
Description Moves absolute synchronously to the specified position.
Parameters
position
Description The position to move to.
Type float
motion_profile
Description The motion profile to move with. See MotionProfile class.
Type MotionProfile
Raises
Type ActuatorException
Description If the move was unsuccessful.
from machinelogic import Machine, MotionProfile
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
# Always home the actuator before starting to ensure position is properly calibrated.
my_actuator.home(timeout=10)
TARGET_POSITION = 150.0 # millimeters
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
my_actuator.move_absolute(
position=TARGET_POSITION, # millimeters
motion_profile=MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK),
timeout=10, # seconds
)
move_absolute_async
Description Moves absolute asynchronously.
Parameters
position
Description The position to move to.
Type float
motion_profile
Description The motion profile to move with. See MotionProfile class.
Type MotionProfile
Raises
Type ActuatorException
Description If the move was unsuccessful.
import time
from machinelogic import Machine, MotionProfile
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
# Always home the actuator before starting to ensure position is properly calibrated.
my_actuator.home(timeout=10)
TARGET_POSITION = 150.0 # millimeters
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
# move_absolute_async will start the move and return without waiting for the move to complete.
my_actuator.move_absolute_async(position=TARGET_POSITION, motion_profile=new_motion_profile)
while my_actuator.state.move_in_progress:
print("move is in progress...")
time.sleep(1)
# end_position will be approx. equal to target_position.
end_position = my_actuator.state.position
print("finished at position: ", end_position)
move_continuous_async
Description Starts a continuous move. The Actuator will keep moving until it is stopped.
Parameters
motion_profile
Description The motion profile to move with. See MotionProfile class. Note: Actuator.move_continuous_async does not support jerk. If jerk is provided in the MotionProfile, a warning will be raised and the move will continue without jerk.
Type MotionProfile
Raises
Type ActuatorException
Description If the move was unsuccessful.
import time
from machinelogic import Machine, MotionProfile
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
# Always home the actuator before starting to ensure position is properly calibrated.
my_actuator.home(timeout=10)
# Continuous motion profile only uses velocity and acceleration.
VELOCITY = 100.0 # mm/s
ACCELERATION = 100.0 # mm/s^2
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION)
# move_continuous_async will start the move and return without waiting for the move to complete.
my_actuator.move_continuous_async(motion_profile=new_motion_profile)
time.sleep(10) # move continuously for ~10 seconds.
my_actuator.stop() # decelerate to stopped.
move_relative
Description Moves relative synchronously by the specified distance.
Parameters
distance
Description The distance to move.
Type float
motion_profile
Description The motion profile to move with. See MotionProfile class.
Type MotionProfile
Raises
Type ActuatorException
Description If the move was unsuccessful.
from machinelogic import Machine, MotionProfile
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
# Always home the actuator before starting to ensure position is properly calibrated.
my_actuator.home(timeout=10)
start_position = my_actuator.state.position
print("starting at position: ", start_position)
TARGET_DISTANCE = 150 # millimeters
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
my_actuator.move_relative(
distance=TARGET_DISTANCE,
motion_profile=new_motion_profile,
)
# first_move_end_position is approx. equal to start_position + target_distance.
first_move_end_position = my_actuator.state.position
print("first move finished at position: ", first_move_end_position)
# move back to starting position
TARGET_DISTANCE = -1 * TARGET_DISTANCE
my_actuator.move_relative(
distance=TARGET_DISTANCE,
motion_profile=new_motion_profile,
)
# approx. equal to start_position,
end_position = my_actuator.state.position
print("finished back at position: ", end_position)
move_relative_async
Description Moves relative asynchronously by the specified distance.
Parameters
distance
Description The distance to move.
Type float
motion_profile
Description The motion profile to move with. See MotionProfile class.
Type MotionProfile
Raises
Type ActuatorException
Description If the move was unsuccessful.
import time
from machinelogic import Machine, MotionProfile
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
# Always home the actuator before starting to ensure position is properly calibrated.
my_actuator.home(timeout=10)
start_position = my_actuator.state.position
print("starting at position: ", start_position)
TARGET_DISTANCE = 150 # millimeters
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
# move_relative_async will start the move and return without waiting for the move to complete.
my_actuator.move_relative_async(distance=TARGET_DISTANCE, motion_profile=new_motion_profile)
while my_actuator.state.move_in_progress:
print("move is in progress...")
time.sleep(1)
# end_position will be approx. equal to start_position + target_distance.
end_position = my_actuator.state.position
print("finished at position", end_position)
stop
Description Stops movement on this Actuator as quickly as possible.
Raises
Type ActuatorException
Description If the Actuator failed to stop.
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
my_actuator.stop()
# The actuator will stop as quickly as possible.
wait_for_move_completion
Description Waits for motion to complete before commencing the next action.
Parameters
timeout
Description The timeout in seconds, after which an exception will be thrown.
Type float
Raises
Type ActuatorException
Description If the request fails or the move did not complete in the allocated amount of time.
from machinelogic import Machine, MotionProfile
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
# Always home the actuator before starting to ensure position is properly calibrated.
my_actuator.home(timeout=10)
TARGET_POSITION = 150.0 # millimeters
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION)
# move_absolute_async will start the move and return without waiting for the move to complete.
my_actuator.move_absolute_async(position=TARGET_POSITION, motion_profile=new_motion_profile)
print("move started...")
my_actuator.wait_for_move_completion(timeout=10)
print("motion complete.")
# end_position will be approx. equal to target_position.
end_position = my_actuator.state.position
print("finished at position: ", end_position)
ActuatorState
Representation of the current state of an Actuator instance. The values in this class are updated in real time to match the physical reality of the Actuator.
end_sensors
Description A tuple representing the state of the [ home, end ] sensors.
Type typing.Tuple[bool, bool]
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.state.end_sensors)
move_in_progress
Description The boolean is True if a move is in progress, otherwise False.
Type bool
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.state.move_in_progress)
output_torque
Description The current torque output of the Actuator.
Type dict
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.state.output_torque)
position
Description The current position of the Actuator.
Type float
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.state.position)
speed
Description The current speed of the Actuator.
Type float
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.state.speed)
ActuatorConfiguration
Representation of the configuration of an Actuator instance. This configuration defines what your Actuator is and how it should behave when work is requested from it.
actuator_type
Description The type of the Actuator.
Type typing.Literal['belt', 'rack_and_pinion', 'rack_and_pinion_v2', 'ball_screw', 'enclosed_ball_screw', 'enclosed_lead_screw', 'indexer', 'indexer_v2', 'electric_cylinder', 'belt_conveyor', 'roller_conveyor', 'pneumatic', 'ac_motor_with_vfd', 'enclosed_timing_belt', 'belt_rack', 'heavy_duty_roller_conveyor', 'timing_belt_conveyor', 'telescopic_column', 'custom']
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.configuration.actuator_type)
controller_id
Description The controller id of the Actuator
Type str
home_sensor
Description The home sensor port, either A or B.
Type typing.Literal['A', 'B']
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.configuration.home_sensor)
name
Description The name of the Actuator.
Type str
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.configuration.name)
units
Description The units that the Actuator functions in.
Type typing.Literal['deg', 'mm']
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.configuration.units)
uuid
Description The Actuator's ID.
Type str
from machinelogic import Machine
machine = Machine()
my_actuator = machine.get_actuator("Actuator")
print(my_actuator.configuration.uuid)
ActuatorGroup
A helper class used to group N-many Actuator instances together so that they can be acted upon as a group. An ActuatorGroup may only contain Actuators that are on the same MachineMotion controller.
E.g.:
machine = Machine()
my_actuator_1 = machine.get_actuator("Actuator 1")
my_actuator_2 = machine.get_actuator("Actuator 2")
actuator_group = ActuatorGroup(my_actuator_1, my_actuator_2)
state
Description The state of the ActuatorGroup.
Type ActuatorGroupState
move_absolute
Description Moves absolute synchronously to the tuple of positions.
Parameters
position
Description The positions to move to. Each value corresponds 1-to-1 with the actuators tuple provided to the constructor.
Type Tuple[float, ...]
motion_profile
Description The motion profile to move with. See MotionProfile class.
Type MotionProfile
Raises
Description If the request fails or the timeout occurs.
from machinelogic import Machine, ActuatorGroup, MotionProfile
machine = Machine()
my_actuator_1 = machine.get_actuator("Actuator 1")
my_actuator_2 = machine.get_actuator("Actuator 2")
# Always home the actuators before starting to ensure position is properly calibrated.
my_actuator_1.home(timeout=10)
my_actuator_2.home(timeout=10)
actuator_group = ActuatorGroup(my_actuator_1, my_actuator_2)
TARGET_POSITIONS = (100.0, 200.0) # (mm - actuator1, mm - actuator2)
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
actuator_group.move_absolute(position=TARGET_POSITIONS, motion_profile=new_motion_profile)
move_absolute_async
Description Moves absolute asynchronously to the tuple of positions.
Parameters
distance
Description The positions to move to. Each value corresponds 1-to-1 with the actuators tuple provided to the constructor.
Type Tuple[float, ...]
motion_profile
Description The motion profile to move with. See MotionProfile class.
Type MotionProfile
Raises
Description If the request fails.
from machinelogic import Machine, ActuatorGroup, MotionProfile
machine = Machine()
my_actuator_1 = machine.get_actuator("Actuator 1")
my_actuator_2 = machine.get_actuator("Actuator 2")
# Always home the actuators before starting to ensure position is properly calibrated.
my_actuator_1.home(timeout=10)
my_actuator_2.home(timeout=10)
actuator_group = ActuatorGroup(my_actuator_1, my_actuator_2)
TARGET_POSITIONS = (75.0, 158.0) # (mm - actuator1, mm - actuator2)
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
# move_absolute_async will start the move and return without waiting for the move to complete.
actuator_group.move_absolute_async(position=TARGET_POSITIONS, motion_profile=new_motion_profile)
print("move started..")
actuator_group.wait_for_move_completion()
print("motion completed.")
move_relative
Description Moves relative synchronously by the tuple of distances.
Parameters
distance
Description The distances to move each Actuator. Each value corresponds 1-to-1 with the actuators tuple provided to the constructor.
Type Tuple[float, ...]
motion_profile
Description The motion profile to move with. See MotionProfile class.
Type MotionProfile
Raises
Description If the request fails or the timeout occurs
from operator import ne
from machinelogic import Machine, ActuatorGroup, MotionProfile
machine = Machine()
my_actuator_1 = machine.get_actuator("Actuator 1")
my_actuator_2 = machine.get_actuator("Actuator 2")
# Always home the actuators before starting to ensure position is properly calibrated.
my_actuator_1.home(timeout=10)
my_actuator_2.home(timeout=10)
actuator_group = ActuatorGroup(my_actuator_1, my_actuator_2)
TARGET_DISTANCES = (-120.0, 240.0) # (mm - actuator1, mm - actuator2)
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
actuator_group.move_relative(distance=TARGET_DISTANCES, motion_profile=new_motion_profile)
move_relative_async
Description Moves relative asynchronously by the tuple of distances.
Parameters
distance
Description The distances to move each Actuator. Each value corresponds 1-to-1 with the actuators tuple provided to the constructor.
Type Tuple[float, ...]
motion_profile
Description The motion profile to move with. See MotionProfile class.
Type MotionProfile
Raises
Description If the request fails.
import time
from machinelogic import Machine, ActuatorGroup, MotionProfile
machine = Machine()
actuator1 = machine.get_actuator("My Actuator #1")
actuator2 = machine.get_actuator("My Actuator #2")
# Always home the actuators before starting to ensure position is properly calibrated.
actuator1.home(timeout=10)
actuator2.home(timeout=10)
actuator_group = ActuatorGroup(actuator1, actuator2)
TARGET_DISTANCES = (-120.0, 240.0) # (mm - actuator1, mm - actuator2)
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
# move_relative_async will start the move and return without waiting for the move to complete.
actuator_group.move_relative_async(distance=TARGET_DISTANCES, motion_profile=new_motion_profile)
while actuator_group.state.move_in_progress:
print("motion is in progress..")
time.sleep(1)
print("motion complete")
stop
Description Stops movement on all Actuators in the group.
Raises
Description If any of the Actuators in the group failed to stop.
wait_for_move_completion
Description Waits for motion to complete on all Actuators in the group.
Parameters
timeout
Description The timeout in seconds, after which an exception will be thrown.
Type float
Raises
Description If the request fails or the move did not complete in the allocated amount of time.
from machinelogic import Machine, ActuatorGroup, MotionProfile
machine = Machine()
my_actuator_1 = machine.get_actuator("Actuator 1")
my_actuator_2 = machine.get_actuator("Actuator 2")
# Always home the actuators before starting to ensure position is properly calibrated.
my_actuator_1.home(timeout=10)
my_actuator_2.home(timeout=10)
actuator_group = ActuatorGroup(my_actuator_1, my_actuator_2)
TARGET_POSITIONS = (75.0, 158.0) # (mm - actuator1, mm - actuator2)
VELOCITY = 150.0 # mm/s
ACCELERATION = 150.0 # mm/s^2
JERK = 150.0 # mm/s^3 OPTIONAL PARAMETER
new_motion_profile = MotionProfile(velocity=VELOCITY, acceleration=ACCELERATION, jerk=JERK)
# move_absolute_async will start the move and return without waiting for the move to complete.
actuator_group.move_absolute_async(position=TARGET_POSITIONS, motion_profile=new_motion_profile)
print("move started..")
actuator_group.wait_for_move_completion()
print("motion completed.")
MotionProfile
MotionProfile: A dataclass that represents the motion profile of a move. args:
velocity (float): The velocity of the move in mm/s
acceleration (float): The acceleration of the move in mm/s^2
jerk (float | None): The jerk of the move in mm/s^3. Defaults to None
If used in a continuous_move, only velocity and acceleration are required.
If jerk is defined, an s-curve profile will be generated. Jerk option is commonly used to limit vibration due to sharp changes in motion profile.
Robot
A software representation of a Robot. It is not recommended that you construct this object yourself. Rather, you should query it from a Machine instance:
E.g.:
machine = Machine()
my_robot = machine.get_robot("Robot")
In this example, "Robot" is the friendly name assigned to the actuator in the MachineLogic configuration page.
configuration
Description The Robot configuration.
Type RobotConfiguration
state
Description The current Robot state.
Type RobotState
compute_forward_kinematics
Description Computes the forward kinematics from joint angles.
Parameters
joint_angles
Description The 6 joint angles, in degrees.
Type JointAnglesDegrees
Returns
Description Cartesian pose, in mm and degrees
Type CartesianPose
Raises
Type ValueError
Description Throws an error if the joint angles are invalid.
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# Joint angles, in degrees
joint_angles = [
176.68, # j1
-35.95, # j2
86.37, # j3
-150.02, # j4
-90.95, # j5
-18.58, # j6
]
computed_robot_pose = my_robot.compute_forward_kinematics(joint_angles)
print(computed_robot_pose)
compute_inverse_kinematics
Description Computes the inverse kinematics from a Cartesian pose.
Parameters
cartesian_position
Description The end effector's pose, in mm and degrees, where the angles are extrinsic Euler angles in XYZ order.
Type CartesianPose
joint_constraints
Description A list of joint constraints. Length of list can be between 1 and number of joints on robot.
Type Optional[List[IGenericJointConstraint]]
seed_position
Description The seed joint angles, in degrees (as start position for IK search)
Type Optional[JointAnglesDegrees]
Returns
Description Joint angles, in degrees.
Type JointAnglesDegrees
Raises
Type ValueError
Description Throws an error if the inverse kinematic solver fails.
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
cartesian_position = [
648.71, # x in millimeters
-313.30, # y in millimeters
159.28, # z in millimeters
107.14, # rx in degrees
-145.87, # ry in degrees
15.13, # rz in degrees
]
computed_joint_angles = my_robot.compute_inverse_kinematics(cartesian_position)
print(computed_joint_angles)
create_sequence
Description Creates a sequence-builder object for building a sequence of robot
Returns
Description A sequence builder object.
Type SequenceBuilder
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# Create an arbitrary Cartesian waypoint, that is 10mm or 10 degrees away from the current position
cartesian_waypoint = [i + 10 for i, _ in my_robot.state.cartesian_position_data]
# Create an arbitrary joint waypoint, that is 10 degrees away from the current joint angles
joint_waypoint = [i + 10 for i, _ in my_robot.state.joint_angles_data]
cartesian_velocity = 100.0 # millimeters per second
cartesian_acceleration = 100.0 # millimeters per second squared
blend_factor_1 = 0.5
reference_frame = [
23.56, # x in millimeters
-125.75, # y in millimeters
5.92, # z in millimeters
0.31, # rx in degrees
0.65, # ry in degrees
90.00, # rz in degrees
]
joint_velocity = 10.0 # degrees per second
joint_acceleration = 10.0 # degrees per second squared
blend_factor_2 = 0.5
with my_robot.create_sequence() as seq:
seq.append_movel(
cartesian_waypoint, cartesian_velocity, cartesian_acceleration, blend_factor_1, reference_frame
)
seq.append_movej(joint_waypoint, joint_velocity, joint_acceleration, blend_factor_2)
# Alternate Form:
seq = my_robot.create_sequence()
seq.append_movel(cartesian_waypoint)
seq.append_movej(joint_waypoint)
my_robot.execute_sequence(seq)
execute_sequence
Description Moves the robot through a specific sequence of joint and linear motions.
Parameters
sequence
Description The sequence of target points.
Type SequenceBuilder
Returns
Description True if successful.
Type bool
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# Create an arbitrary Cartesian waypoint, that is 10mm or 10 degrees away from the current position
cartesian_waypoint = [i + 10 for i, _ in my_robot.state.cartesian_position_data]
# Create an arbitrary joint waypoint, that is 10 degrees away from the current joint angles
joint_waypoint = [i + 10 for i, _ in my_robot.state.joint_angles_data]
cartesian_velocity = 100.0 # millimeters per second
cartesian_acceleration = 100.0 # millimeters per second squared
blend_factor_1 = 0.5
joint_velocity = 10.0 # degrees per second
joint_acceleration = 10.0 # degrees per second squared
blend_factor_2 = 0.5
seq = my_robot.create_sequence()
seq.append_movel(
cartesian_waypoint, cartesian_velocity, cartesian_acceleration, blend_factor_1
)
seq.append_movej(joint_waypoint, joint_velocity, joint_acceleration, blend_factor_2)
my_robot.execute_sequence(seq)
execute_sequence_async
Description Moves the robot through a specific sequence of joint and linear motions asynchronously.
Parameters
sequence
Description The sequence of target points.
Type SequenceBuilder
Returns
Description True if successful.
Type bool
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# Create an arbitrary Cartesian waypoint, that is 10mm or 10 degrees away from the current position
cartesian_waypoint = [i + 10 for i, _ in my_robot.state.cartesian_position_data]
# Create an arbitrary joint waypoint, that is 10 degrees away from the current joint angles
joint_waypoint = [i + 10 for i, _ in my_robot.state.joint_angles_data]
cartesian_velocity = 100.0 # millimeters per second
cartesian_acceleration = 100.0 # millimeters per second squared
blend_factor_1 = 0.5
joint_velocity = 10.0 # degrees per second
joint_acceleration = 10.0 # degrees per second squared
blend_factor_2 = 0.5
seq = my_robot.create_sequence()
seq.append_movel(
cartesian_waypoint, cartesian_velocity, cartesian_acceleration, blend_factor_1
)
seq.append_movej(joint_waypoint, joint_velocity, joint_acceleration, blend_factor_2)
my_robot.execute_sequence_async(seq)
print("Robot is executing sequence asynchronously.")
my_robot.wait_for_motion_completion()
print("Robot has finished executing sequence.")
move_stop
Description Stops the robot current movement.
Returns
Description True if the robot was successfully stopped, False otherwise.
Type bool
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
my_robot.move_stop()
movej
Description Moves the robot to a specified joint position.
Parameters
target
Description The target joint angles, in degrees.
Type JointAnglesDegrees
velocity
Description The joint velocity to move at, in degrees per second.
Type DegreesPerSecond
acceleration
Description The joint acceleration to move at, in degrees per second squared.
Type DegreesPerSecondSquared
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
joint_velocity = 10.0 # degrees per second
joint_acceleration = 10.0 # degrees per second squared
# Joint angles, in degrees
joint_angles = [
86.0, # j1
0.0, # j2
88.0, # j3
0.0, # j4
91.0, # j5
0.0, # j6
]
my_robot.movej(
joint_angles,
joint_velocity,
joint_acceleration,
)
movej_async
Description Moves the robot to a specified joint position asynchronously.
Parameters
target
Description The target joint angles, in degrees.
Type JointAnglesDegrees
velocity
Description The joint velocity to move at, in degrees per second.
Type DegreesPerSecond
acceleration
Description The joint acceleration to move at, in degrees per second squared.
Type DegreesPerSecondSquared
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
joint_velocity = 10.0 # degrees per second
joint_acceleration = 10.0 # degrees per second squared
# Joint angles, in degrees
joint_angles = [
86.0, # j1
0.0, # j2
88.0, # j3
0.0, # j4
91.0, # j5
0.0, # j6
]
my_robot.movej_async(
joint_angles,
joint_velocity,
joint_acceleration,
)
print("Robot is moving asynchronously to the specified joint angles.")
my_robot.wait_for_motion_completion()
print("Robot has finished moving to the specified joint angles.")
movel
Description Moves the robot to a specified Cartesian position.
Parameters
target
Description The end effector's pose, in mm and degrees, where the angles are extrinsic Euler angles in XYZ order.
Type CartesianPose
velocity
Description The velocity to move at, in mm/s.
Type MillimetersPerSecond
acceleration
Description The acceleration to move at, in mm/s^2.
Type MillimetersPerSecondSquared
reference_frame
Description The reference frame to move relative to. If None, the robot's base frame is used.
Type Optional[CartesianPose]
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
linear_velocity = 100.0 # millimeters per second
linear_acceleration = 100.0 # millimeters per second squared
# Target Cartesian pose, in millimeters and degrees
cartesian_pose = [
-267.8, # x in millimeters
-89.2, # y in millimeters
277.4, # z in millimeters
-167.8, # rx in degrees
0, # ry in degrees
-77.8, # rz in degrees
]
reference_frame = [
23.56, # x in millimeters
-125.75, # y in millimeters
5.92, # z in millimeters
0.31, # rx in degrees
0.65, # ry in degrees
90.00, # rz in degrees
]
my_robot.movel(
cartesian_pose,
linear_velocity, # Optional
linear_acceleration, # Optional
reference_frame, # Optional
)
movel_async
Description Moves the robot to a specified Cartesian position asynchronously.
Parameters
target
Description The end effector's pose, in mm and degrees, where the angles are extrinsic Euler angles in XYZ order.
Type CartesianPose
velocity
Description The velocity to move at, in mm/s.
Type MillimetersPerSecond
acceleration
Description The acceleration to move at, in mm/s^2.
Type MillimetersPerSecondSquared
reference_frame
Description The reference frame to move relative to. If None, the robot's base frame is used.
Type Optional[CartesianPose]
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
linear_velocity = 100.0 # millimeters per second
linear_acceleration = 100.0 # millimeters per second squared
# Target Cartesian pose, in millimeters and degrees
cartesian_pose = [
-267.8, # x in millimeters
-89.2, # y in millimeters
277.4, # z in millimeters
-167.8, # rx in degrees
0, # ry in degrees
-77.8, # rz in degrees
]
reference_frame = [
23.56, # x in millimeters
-125.75, # y in millimeters
5.92, # z in millimeters
0.31, # rx in degrees
0.65, # ry in degrees
90.00, # rz in degrees
]
my_robot.movel_async(
cartesian_pose,
linear_velocity, # Optional
linear_acceleration, # Optional
reference_frame, # Optional
)
print("Robot is moving asynchronously to the specified Cartesian pose.")
my_robot.wait_for_motion_completion()
print("Robot has finished moving to the specified Cartesian pose.")
on_log_alarm
Description Set a callback to the log alarm.
Parameters
callback
Description A callback function to be called when a robot alarm is received.
Type Callable[[IRobotAlarm], None]
Returns
Description The callback ID.
Type int
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# The functon defined here is called when the specified alarm occurs
def handle_log_alarm(alarm):
print(alarm.level, alarm.error_code, alarm.description)
my_robot.on_log_alarm(handle_log_alarm)
on_system_state_change
Description Registers a callback for system state changes.
Parameters
callback
Description The callback function.
Type Callable[[RobotOperationalState, RobotSafetyState], None]
Returns
Description The callback ID.
Type int
from machinelogic import Machine
from machinelogic.machinelogic.robot import RobotOperationalState, RobotSafetyState
machine = Machine()
my_robot = machine.get_robot("Robot")
# The function defined here is called when the specified state change occurs
def handle_state_change(robot_operational_state: RobotOperationalState, safety_state: RobotSafetyState):
"""
A function that is called when the specified state change occurs.
Args:
robot_operational_state (RobotOperationalState): The current operational state of the robot.
safety_state (RobotSafetyState): The current safety state of the robot.
"""
print(robot_operational_state, safety_state)
callback_id = my_robot.on_system_state_change(handle_state_change)
print(callback_id)
reconnect
Description It will disconnect then reconnect the MachineMotion to the robot.
Parameters
timeout
Description The timeout in seconds, after which an exception will be thrown, default is 15 seconds.
Type Union[float, None]
Returns
Description True if successful.
Type bool
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# if no timeout argument is provided, the default timeout is 15 seconds
did_reconnect = my_robot.reconnect()
print(did_reconnect)
reset
Description Attempts to reset the robot to a normal operational state.
Returns
Description True if successful.
Type bool
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
did_reset = my_robot.reset()
print(did_reset)
# Robot state should be 'Normal'
print(my_robot.state.operational_state)
set_payload
Description Sets the payload of the robot.
Parameters
payload
Description The payload, in kg.
Type Kilograms
Returns
Description True if successful.
Type bool
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# Weight in Kilograms
weight = 2.76
is_successful = my_robot.set_payload(weight)
print(is_successful)
set_tcp_offset
Description Sets the tool center point offset.
Parameters
tcp_offset
Description The TCP offset, in mm and degrees, where the angles are extrinsic Euler angles in XYZ order.
Type CartesianPose
Returns
Description True if the TCP offset was successfully set, False otherwise.
Type bool
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# This offset will be applied in reference
# to the end effector coordinate system
cartesian_offset = [
10.87, # x in millimeters
-15.75, # y in millimeters
200.56, # z in millimeters
0.31, # rx degrees
0.65, # ry degrees
0.00, # rz degrees
]
is_successful = my_robot.set_tcp_offset(cartesian_offset)
print(is_successful)
set_tool_digital_output
Description Sets the value of a tool digital output.
Parameters
pin
Description The pin number.
Type int
value
Description The value to set, where 1 is high and 0 is low.
Type int
Returns
Description True if successful.
Type bool
from machinelogic import Machine
machine = Machine()
# New robot must be configured in the Configuration pane
my_robot = machine.get_robot("Robot")
# digital output identifier
output_pin = 1
value = 0
is_successful = my_robot.set_tool_digital_output(output_pin, value)
print(is_successful)
teach_mode
Description Put the robot into teach mode (i.e., freedrive).
Returns
Description A context manager that will exit teach mode when it is closed.
Type TeachModeContextManager
import time
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
with my_robot.teach_mode(): # When all arguments inside this statement are complete, teach mode ends automatically
print("Robot is now in teach mode for 5 seconds")
time.sleep(5)
# Robot should be in 'Freedrive'
print(my_robot.state.operational_state)
time.sleep(1)
time.sleep(1)
# Robot should be back to 'Normal'
print(my_robot.state.operational_state)
wait_for_motion_completion
Description Waits for the robot to complete its current motion. Used in asynchronous movements.
Parameters
timeout
Description The timeout in seconds, after which an exception will be thrown.
Type Optional[float]
Returns
Description True if successful.
Type bool
Raises
Type RobotException
Description If the request fails or the move did not complete in the allocated amount of time.
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
joint_velocity = 10.0 # degrees per second
joint_acceleration = 10.0 # degrees per second squared
# Joint angles, in degrees
joint_angles = [
86.0, # j1
0.0, # j2
88.0, # j3
0.0, # j4
91.0, # j5
0.0, # j6
]
my_robot.movej_async(
joint_angles,
joint_velocity,
joint_acceleration,
)
print("Robot is moving asynchronously to the specified joint angles.")
my_robot.wait_for_motion_completion()
print("Robot has finished moving to the specified joint angles.")
RobotState
A representation of the robot current state.
(Deprecated) cartesian_position
Description (Deprecated) Use cartesian_position_data instead.
Type CartesianPose
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# Note: cartesian_position has been deprecated in favor of cartesian_position_data
end_effector_pose = my_robot.state.cartesian_position
end_effector_position_mm = end_effector_pose[:3]
end_effector_orientation_euler_xyz_deg = end_effector_pose[-3:]
print(f"End effector's pose: {end_effector_pose}")
print(f"End effector's Cartesian position: {end_effector_position_mm}")
print(f"End effector's Euler XYZ orientation: {end_effector_orientation_euler_xyz_deg}")
cartesian_position_data
Description A tuple of the robot current Cartesian position and the timestamp in seconds and milliseconds to epoch.
Type tuple[CartesianPose, Timestamp]
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
end_effector_pose = my_robot.state.cartesian_position_data[0]
timestamp = my_robot.state.cartesian_position_data[1]
end_effector_position_mm = end_effector_pose[:3]
end_effector_orientation_euler_xyz_deg = end_effector_pose[-3:]
print(f"End effector's pose: {end_effector_pose}")
print(f"End effector's Cartesian position: {end_effector_position_mm}")
print(f"End effector's Euler XYZ orientation: {end_effector_orientation_euler_xyz_deg}")
print(f"Timestamp: {timestamp}")
(Deprecated) joint_angles
Description (Deprecated) Use joint_angles_data instead.
Type JointAnglesDegrees
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
# Note: joint_angles has been deprecated in favor of joint_angles_data
print(my_robot.state.joint_angles)
joint_angles_data
Description A tuple of the robot current joint angles and the timestamp in seconds and milliseconds to epoch.
Type tuple[JointAnglesDegrees, Timestamp]
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
joint_angles = my_robot.state.joint_angles_data[0]
timestamp = my_robot.state.joint_angles_data[1]
print(f"Joint angles: {joint_angles}")
print(f"Timestamp: {timestamp}")
move_in_progress
Description Check if the robot is currently moving.
Type bool
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.state.move_in_progress)
operational_state
Description The current robot operational state.
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.state.operational_state)
safety_state
Description The current robot safety state.
Type RobotSafetyState
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.state.safety_state)
tcp_offset
Description The tool center point (TCP) offset, in mm and degrees, where the angles are extrinsic Euler angles in XYZ order.
Type CartesianPose
get_digital_input_value
Description Returns the value of a digital input at a given pin.
Parameters
pin
Description The pin number.
Type int
Returns
Description True if the pin is high, False otherwise.
Type None
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.state.get_digital_input_value(0))
RobotOperationalState
Description: The robot's operational state.
OFFLINE= 0
NON_OPERATIONAL= 1
FREEDRIVE= 2
NORMAL= 3
UNKNOWN= 4
NEED_MANUAL_INTERVENTION= 5
RobotSafetyState
Description: The robot's safety state.
NORMAL= 0
EMERGENCY_STOP= 2
REDUCED_SPEED= 3
SAFEGUARD_STOP= 4
UNKNOWN= 5
RobotConfiguration
A representation of the configuration of a Robot instance. This configuration defines what your Robot is and how it should behave when work is requested from it.
_ros_address
Description The address of the ROS-container or the robot.
Type str
cartesian_velocity_limit
Description The maximum Cartesian velocity of the robot, in mm/s.
Type MillimetersPerSecond | None
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.configuration.cartesian_velocity_limit)
joint_velocity_limit
Description The robot joints' maximum angular velocity, in deg/s.
Type DegreesPerSecond | None
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.configuration.joint_velocity_limit)
name
Description The friendly name of the robot.
Type str
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.configuration.name)
robot_type
Description The robot's type.
Type str
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.configuration.robot_type)
uuid
Description The robot's ID.
Type str
from machinelogic import Machine
machine = Machine()
my_robot = machine.get_robot("Robot")
print(my_robot.configuration.uuid)
Timestamp
A timestamp since epoch, UTC attributes:
secs: seconds since epoch
nsecs: nanoseconds since epoch
GenericJointConstraint
A representation of a generic joint constraint. To be used within the compute_inverse_kinematics method of a robot.
joint_index
Description The 1-based index of the robot joint
Type int
position
Description The angle of the joint in degrees
Type float
tolerance_above
Description The tolerance above the position in degrees
Type float
tolerance_below
Description The tolerance below the position in degrees
Type float
weighting_factor
Description A weighting factor for this constraint (denotes relative importance to other constraints, closer to zero means less important).
Type float
SequenceBuilder
A builder for a sequence of moves.
append_movej
Description Append a movej to the sequence.
Parameters
target
Description The target joint angles, in degrees.
Type JointAnglesDegrees
velocity
Description The velocity of the move, in degrees per second. Defaults to 10.0.
Type DegreesPerSecond
acceleration
Description The acceleration of the move, in degrees per second squared. Defaults to 10.0.
Type DegreesPerSecondSquared
blend_radius
Description The blend radius of the move, in millimeters. Defaults to 0.0.
Type Millimeters
Returns
Description The builder.
Type SequenceBuilder
append_movel
Description Append a movel to the sequence.
Parameters
target
Description The target pose.
Type CartesianPose
velocity
Description The velocity of the move, in millimeters per second. Defaults to 100.0.
Type MillimetersPerSecond
acceleration
Description The acceleration of the move, in millimeters per second squared. Defaults to 100.0.
Type MillimetersPerSecondSquared
blend_radius
Description The blend radius of the move, in millimeters. Defaults to 0.0.
Type Millimeters
reference_frame
Description The reference frame for the target pose. Defaults to None.
Type CartesianPose
Returns
Description The builder.
Type SequenceBuilder
DigitalInput
A software representation of an DigitalInput. It is not recommended that you construct this object yourself. Rather, you should query it from a Machine instance.
configuration
Description The configuration of the DigitalInput.
state
Description The state of the DigitalInput.
Type DigitalInputState
from machinelogic import Machine
machine = Machine()
my_input = machine.get_input("Input")
if my_input.state.value:
print(f"{my_input.configuration.name} is HIGH")
else:
print(f"{my_input.configuration.name} is LOW")
DigitalInputState
Representation of the current state of an DigitalInput/DigitalOutput instance.
value
Description The current value of the IO pin. True means high, while False means low. This is different from active/inactive, which depends on the active_high configuration.
Type bool
DigitalInputConfiguration
Representation of the configuration of an DigitalInput/DigitalOutput. This configuration is established by the configuration page in MachineLogic.
active_high
Description The value that needs to be set to consider the DigitalInput/DigitalOutput as active.
Type bool
controller_id
Description The MachineMotion controller id of the DigitalInput/DigitalOutput.
Type str
controller_port
Description The MachineMotion controller port of the DigitalInput/DigitalOutput.
Type int
device_id
Description The device number of the DigitalInput/DigitalOutput.
Type int
name
Description The name of the DigitalInput/DigitalOutput.
Type str
pin
Description The pin number of the DigitalInput/DigitalOutput.
Type int
uuid
Description The unique ID of the DigitalInput/DigitalOutput.
Type str
DigitalOutput
A software representation of an Output. It is not recommended that you construct this object yourself. Rather, you should query it from a Machine instance.
configuration
Description The configuration of the Output.
write
Description Writes the value into the Output, with True being high and False being low.
Parameters
value
Description The value to write to the Output.
Type bool
Raises
Description If we fail to write the value to the Output.
from machinelogic import Machine, MachineException, DigitalOutputException
machine = Machine()
my_output = machine.get_output("Output")
my_output.write(True) # Write "true" to the Output
my_output.write(False) # Write "false" to the Output
DigitalOutputConfiguration
Representation of the configuration of an DigitalInput/DigitalOutput. This configuration is established by the configuration page in MachineLogic.
active_high
Description The value that needs to be set to consider the DigitalInput/DigitalOutput as active.
Type bool
controller_id
Description The MachineMotion controller id of the DigitalInput/DigitalOutput.
Type str
controller_port
Description The MachineMotion controller port of the DigitalInput/DigitalOutput.
Type int
device_id
Description The device number of the DigitalInput/DigitalOutput.
Type int
name
Description The name of the DigitalInput/DigitalOutput.
Type str
pin
Description The pin number of the DigitalInput/DigitalOutput.
Type int
uuid
Description The unique ID of the DigitalInput/DigitalOutput.
Type str
Pneumatic
A software representation of a Pneumatic. It is not recommended that you construct this object yourself. Rather, you should query it from a Machine instance:
E.g.:
machine = Machine()
my_pneumatic = machine.get_pneumatic("Pneumatic")
In this example, "Pneumatic" is the friendly name assigned to a Pneumatic in the MachineLogic configuration page.
configuration
Description The configuration of the actuator.
state
Description The state of the actuator.
Type typing.Literal['pushed', 'pulled', 'transition', 'unknown']
idle_async
Description Idles the Pneumatic.
Raises
Type PneumaticException
Description If the idle was unsuccessful.
pull_async
Description Pulls the Pneumatic.
Raises
Type PneumaticException
Description If the pull was unsuccessful.
push_async
Description Pushes the Pneumatic.
Raises
Type PneumaticException
Description If the push was unsuccessful.
PneumaticConfiguration
Representation of a Pneumatic configuration.
controller_id
Description The MachineMotion controller id.
Type str
controller_port
Description The MachineMotion controller port of the io module that controls the pneumatic axis.
Type int
device_id
Description The device id of the io module that controls the pneumatic axis.
Type int
input_pin_pull
Description The optional pull in pin.
Type typing.Optional[int]
input_pin_push
Description The optional push in pin.
Type typing.Optional[int]
name
Description The name of the Pneumatic.
Type str
output_pin_pull
Description The pull out pin of the axis.
Type int
output_pin_push
Description The push out pin of the axis.
Type int
uuid
Description The ID of the Pneumatic.
Type str
ACMotor
A software representation of an AC Motor. It is not recommended that you construct this object yourself. Rather, you should query it from a Machine instance:
E.g.:
machine = Machine()
my_ac_motor = machine.get_ac_motor("AC Motor")
In this example, "AC Motor" is the friendly name assigned to an AC Motor in the MachineLogic configuration page.
configuration
Description The configuration of the ACMotor.
Type ACMotorConfiguration
move_forward
Description Begins moving the AC Motor forward.
Raises
Type ACMotorException
Description If the move was unsuccessful.
from time import sleep
from machinelogic import Machine
machine = Machine()
my_ac_motor = machine.get_ac_motor("AC Motor")
my_ac_motor.move_forward()
sleep(10)
my_ac_motor.stop()
move_reverse
Description Begins moving the AC Motor in reverse.
Raises
Type ACMotorException
Description If the move was unsuccessful.
import time
from machinelogic import Machine
machine = Machine()
my_ac_motor = machine.get_ac_motor("AC Motor")
# Move the AC motor in reverse
my_ac_motor.move_reverse()
# The AC motor will stop moving if the program terminates
time.sleep(10)
stop
Description Stops the movement of the AC Motor.
Raises
Type ACMotorException
Description If the stop was unsuccessful.
import time
from machinelogic import Machine
machine = Machine()
my_ac_motor = machine.get_ac_motor("AC Motor")
# Move the AC Motor forwards
my_ac_motor.move_forward()
# Do something here
time.sleep(10)
my_ac_motor.stop()
ACMotorConfiguration
Representation of a ACMotor configuration.
controller_id
Description The MachineMotion controller id
Type str
controller_port
Description The MachineMotion controller port of the io module that controls the ac_motor.
Type int
device_id
Description The device id of the io module of the ac_motor.
Type int
name
Description The name of the Pneumatic.
Type str
output_pin_direction
Description The push out pin of the axis.
Type int
output_pin_move
Description The pull out pin of the axis.
Type int
uuid
Description The ID of the Pneumatic.
Type str
PathFollower
Path Follower: A Path Follower Object is a group of Actuators, Digital Inputs and Digital Outputs that enable execution of smooth predefined paths. These paths are defined with G-Code instructions. See Vention's G-code interface documentation for a list of supported commands: https://vention.io/resources/guides/path-following-interface-391#parser-configuration
state
Description Current state of the path follower
Type PathFollowerState
add_tool
Description Add a tool to be referenced by the M(3-5) $[tool_id] commands
Parameters
tool_id
Description Unique integer defining tool id.
Type int
m3_output
Description Output to map to the M3 Gcode command
Type DigitalOutput
m4_output
Description Optional, Output to map to the M4 Gcode command
Type Union[IDigitalOutput, None]
Raises
Type PathFollowerException
Description If the tool was not properly added.
from machinelogic import Machine, PathFollower
machine = Machine()
x_axis = machine.get_actuator("X_Actuator")
y_axis = machine.get_actuator("Y_Actuator")
m3_output = machine.get_output("M3_Output")
m4_output = machine.get_output("M4_Output")
GCODE = """
G90 ; Absolute position mode
G0 X60 Y110 F1200 ; Rapid move at 1200 mm/minute
M3 $1 ; Start tool 1 in clockwise direction
G1 X110 Y110 F1000 ; Travel move at 1000 mm/minute
M4 $1 ; counter clockwise now
G0 X50 Y50
M5 $1 ; Stop tool 1
G0 X1 Y1
"""
# Create PathFollower instance
path_follower = PathFollower(x_axis, y_axis)
# Associate a digital output with a GCode tool number
path_follower.add_tool(1, m3_output, m4_output) # clockwise # counterclockwise
path_follower.start_path(GCODE)
start_path
Description Start the path, returns when path is complete
Parameters
gcode
Description Gcode path
Type str
Raises
Type PathFollowerException
Description If failed to run start_path
from machinelogic import Machine, PathFollower
machine = Machine()
# must be defined in ControlCenter
x_axis = machine.get_actuator("X_Actuator")
y_axis = machine.get_actuator("Y_Actuator")
GCODE = """
(Operational mode commands)
G90 ; Absolute position mode
G90.1 ; Absolute arc centre
G21 ; Use millimeter units
G17 ; XY plane arcs
G64 P0.5 ; Blend move mode, 0.5 mm tolerance
(Movement and output commands)
G0 X60 Y110 F1200 ; Rapid move at 1200 mm/minute
G1 X110 Y110 F1000 ; Travel move at 1000 mm/minute
G2 X110 Y10 I100 J60 ; Clockwise arc
G1 X60 Y10
G2 X60 Y110 I60 J60
G4 P1.0 ; Dwell for 1 second
G0 X1 Y1
"""
# Create PathFollower instance
path_follower = PathFollower(x_axis, y_axis)
# Run your Gcode
path_follower.start_path(GCODE)
start_path_async
Description Start the path, nonblocking, returns immediately
Parameters
gcode
Description Gcode path
Type str
Raises
Type PathFollowerException
Description If failed to run start_path_async
from machinelogic import Machine, PathFollower
import time
machine = Machine()
# must be defined in ControlCenter
x_axis = machine.get_actuator("X_Actuator")
y_axis = machine.get_actuator("Y_Actuator")
GCODE = """
(Operational mode commands)
G90 ; Absolute position mode
G90.1 ; Absolute arc centre
G21 ; Use millimeter units
G17 ; XY plane arcs
G64 P0.5 ; Blend move mode, 0.5 mm tolerance
(Movement and output commands)
G0 X60 Y110 F1200 ; Rapid move at 1200 mm/minute
G1 X110 Y110 F1000 ; Travel move at 1000 mm/minute
G2 X110 Y10 I100 J60 ; Clockwise arc
G1 X60 Y10
G2 X60 Y110 I60 J60
G4 P1.0 ; Dwell for 1 second
G0 X1 Y1
"""
path_follower = PathFollower(x_axis, y_axis)
# Run your Gcode
path_follower.start_path_async(GCODE)
PATH_IN_PROGRESS = True
while PATH_IN_PROGRESS:
time.sleep(0.5)
path_state = path_follower.state
PATH_IN_PROGRESS = path_state.running
print(
{
"running": path_state.running,
"line_number": path_state.line_number,
"current_command": path_state.current_command,
"error": path_state.error,
"speed": path_state.speed,
"acceleration": path_state.acceleration,
}
)
stop_path
Description Abruptly stop the path following procedure.
Raises
Type PathFollowerException
Description If failed to stop path
wait_for_path_completion
Description Wait for the path to complete
from machinelogic import Machine, PathFollower
machine = Machine()
# must be defined in ControlCenter
x_axis = machine.get_actuator("X_Actuator")
y_axis = machine.get_actuator("Y_Actuator")
GCODE = """
(Operational mode commands)
G90 ; Absolute position mode
G90.1 ; Absolute arc centre
G21 ; Use millimeter units
G17 ; XY plane arcs
G64 P0.5 ; Blend move mode, 0.5 mm tolerance
(Movement and output commands)
G0 X60 Y110 F1200 ; Rapid move at 1200 mm/minute
G1 X110 Y110 F1000 ; Travel move at 1000 mm/minute
G2 X110 Y10 I100 J60 ; Clockwise arc
G1 X60 Y10
G2 X60 Y110 I60 J60
G4 P1.0 ; Dwell for 1 second
G0 X1 Y1
"""
# Create PathFollower instance
path_follower = PathFollower(x_axis, y_axis)
# Run your Gcode asynchronously
path_follower.start_path_async(GCODE)
# Waits for path completion before continuing with program
path_follower.wait_for_path_completion()
print("Path Complete")
PathFollowerState
PathFollower State
acceleration
Description The current tool acceleration in millimeters/second^2
Type float
current_command
Description In-progress command of gcode script.
Type typing.Optional[str]
error
Description A description of errors encountered during path execution.
Type typing.Optional[str]
line_number
Description Current line number in gcode script.
Type int
running
Description True if path following in progress.
Type bool
speed
Description The current tool speed in millimeters/second
Type float
Scene
A software representation of the scene containing assets that describe and define reference frames and targets for robots.
Only a single instance of this object should exist in your program.
get_calibration_frame
Description Gets a calibration frame from scene assets by name
Parameters
name
Description Friendly name of the calibration frame asset
Type str
Returns
Description The found calibration frame
Type CalibrationFrame
Raises
Type SceneException
Description If the scene asset is not found
from machinelogic import Machine
machine = Machine()
scene = machine.get_scene()
# Assuming we have a calibration frame defined
# in Scene Assets called "calibration_frame_1"
calibration_frame = scene.get_calibration_frame("calibration_frame_1")
default_value = calibration_frame.get_default_value()
print(default_value)
CalibrationFrame
A calibration frame, as defined in the scene assets pane, is represented in software. It is measured in millimeters and degrees, with angles given as extrinsic Euler angles in XYZ order.
get_calibrated_value
Description Gets the calibration frame's calibrated values.
Returns
Description The calibrated value of the calibration frame in mm and degrees, where the angles are extrinsic Euler angles in XYZ order.
Type CartesianPose
Raises
Type SceneException
Description If failed to get the calibrated value
from machinelogic import Machine
machine = Machine()
scene = machine.get_scene()
# Assuming we have a calibration frame defined
# in Scene Assets called "calibration_frame_1"
calibration_frame = scene.get_calibration_frame("calibration_frame_1")
calibrated_value = calibration_frame.get_calibrated_value()
print(calibrated_value)
get_default_value
Description Gets the calibration frame's default values.
Returns
Description The nominal value of the calibration frame in mm and degrees, where the angles are extrinsic Euler angles in XYZ order.
Type CartesianPose
Raises
Type SceneException
Description If failed to get the default value
from machinelogic import Machine
machine = Machine()
scene = machine.get_scene()
# Assuming we have a calibration frame defined
# in Scene Assets called "calibration_frame_1"
calibration_frame = scene.get_calibration_frame("calibration_frame_1")
default_value = calibration_frame.get_default_value()
print(default_value)
set_calibrated_value
Description Sets the calibration frame's calibrated values.
Parameters
frame
Description The calibrated values of the Calibration Frame in mm and degrees, where the angles are extrinsic Euler angles in XYZ order.
Type CartesionPose
Raises
Type SceneException
Description If failed to set the calibrated value
from machinelogic import Machine
machine = Machine()
scene = machine.get_scene()
# Assuming we have a calibration frame defined
# in Scene Assets called "calibration_frame_1"
calibration_frame = scene.get_calibration_frame("calibration_frame_1")
# CartesianPose in mm and degrees, where the angles are
# extrinsic Euler angles in XYZ order.
calibrated_cartesian_pose = [100, 100, 50, 90, 90, 0]
calibration_frame.set_calibrated_value(calibrated_cartesian_pose)
ActuatorException
An exception thrown by an Actuator
Args:
VentionException (VentionException): Super class
with_traceback
Description Exception.with_traceback(tb) --
MachineException
An exception thrown by the Machine
Args:
Exception (VentionException): Super class
with_traceback
Description Exception.with_traceback(tb) --
RobotException
An exception thrown by a Robot
Args:
VentionException (VentionException): Super class
with_traceback
Description Exception.with_traceback(tb) --
MachineMotionException
An exeption thrown by a MachineMotion
Args:
VentionException (VentionException): Super class
with_traceback
Description Exception.with_traceback(tb) --
DigitalInputException
An exception thrown by an INput
Args:
VentionException (VentionException): Super class
with_traceback
Description Exception.with_traceback(tb) --
DigitalOutputException
An exception thrown by an Output
Args:
VentionException (VentionException): Super class
with_traceback
Description Exception.with_traceback(tb) --
ActuatorGroupException
An exception thrown by an ActuatorGroup
Args:
VentionException (VentionException): Super class
with_traceback
Description Exception.with_traceback(tb) --
PathFollowingException
An exception thrown by a path following operation
Args:
VentionException(__type__): Super class
with_traceback
Description Exception.with_traceback(tb) --