Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Documented 82 items across 9 files #18

Open
wants to merge 4 commits into
base: dev-doc
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
114 changes: 114 additions & 0 deletions examples/LBRJointSineOverlay.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,57 @@


class LBRJointSineOverlayClient(fri.LBRClient):
"""
Extends the `fri.LBRClient` to add a sine wave overlay to joint positions,
with customizable frequency, amplitude, and filter coefficients. It synchronizes
with the robot's state changes and commands new joint positions based on the
calculated offset values.

Attributes:
joint_mask (npndarray[bool]): Used to specify which joints of a robot are
masked for the sine overlay operation. It filters out unwanted joint
positions from being modified by the sine wave.
freq_hz (float): Used to specify a frequency value in Hertz, representing
the rate at which the sine wave is generated. It is stored as a class
instance variable.
ampl_rad (float): Used to calculate the amplitude of a sine wave that will
be applied to specific joints of a robot, with units of radians.
filter_coeff (float): Used as a coefficient for a low-pass filter in the
generation of the sine wave offset values.
It appears to be used to smoothly ramp up or down the amplitude of the
sine wave over time.
offset (float|npfloat32): Updated using a low-pass filter, with its current
value being mixed (filtered) with a new calculated offset value based
on sine wave amplitude.
phi (float): 0 by default, representing a phase angle incremented over
time to generate sine wave joint position offsets. It resets when the
session state changes to MONITORING_READY.
step_width (float|None): Calculated based on the frequency (freq_hz),
sample time, and 2 * pi in radians. It represents a small angle increment
for sine wave generation.

"""
def __init__(self, joint_mask, freq_hz, ampl_rad, filter_coeff):
"""
Initializes its attributes, including joint mask, frequency, amplitude,
filter coefficient, and phase offsets. It also calls the parent class's
constructor through super().

Args:
joint_mask (bool | np.ndarray): 2-dimensional, where each value
represents whether a joint should be considered or not for frequency
filtering. It is typically used to select which joints are relevant
for analysis.
freq_hz (float): Associated with frequency measurement, indicating a
signal's oscillation rate measured in Hertz (Hz).
ampl_rad (float): Named `ampl_rad`. It represents an amplitude value
expressed in radians, suggesting it will be used for calculations
involving rotational or circular quantities.
filter_coeff (float): Used as a coefficient for filtering purposes,
likely related to a low-pass filter or a similar mathematical
operation involving signal processing.

"""
super().__init__()
self.joint_mask = joint_mask
self.freq_hz = freq_hz
Expand All @@ -24,6 +74,20 @@ def monitor(self):
pass

def onStateChange(self, old_state, new_state):
"""
Resets certain parameters when the robot session enters the MONITORING_READY
state, preparing it for sine wave motion generation. It also updates a
step width calculation based on frequency and sample time.

Args:
old_state (float | int): An enumeration member from fri.ESessionState.
It represents the previous state of the session before it was
changed to the new state passed as `new_state`.
new_state (EnumMember[fri.ESessionState] | None): Implicitly a state
variable representing a session state, updated from an old state,
indicating a change in the system's operational status.

"""
print(f"Changed state from {old_state} to {new_state}")
if new_state == fri.ESessionState.MONITORING_READY:
self.offset = 0.0
Expand All @@ -33,11 +97,23 @@ def onStateChange(self, old_state, new_state):
)

def waitForCommand(self):
"""
Sets the joint positions of a robot to match current Ipo joint positions
using numpy float32 data type, presumably preparing the robot for a commanded
action or synchronization with a sine wave motion.

"""
self.robotCommand().setJointPosition(
self.robotState().getIpoJointPosition().astype(np.float32)
)

def command(self):
"""
Updates the joint position of a robot by applying a sinusoidal offset to
each specified joint, filtered using an exponential decay coefficient. The
updated joint positions are then sent as a command to the robot.

"""
new_offset = self.ampl_rad * math.sin(self.phi)
self.offset = (self.offset * self.filter_coeff) + (
new_offset * (1.0 - self.filter_coeff)
Expand All @@ -51,7 +127,35 @@ def command(self):


def args_factory():
"""
Defines a command-line interface for an application using the `argparse`
library. It creates arguments for various parameters, such as hostnames, ports,
joint masks, and filter coefficients, along with their data types and default
values.

Returns:
argparseNamespace: A collection of arguments parsed from command-line
input, including their values and help information. This object can be
accessed like an attribute, e.g., `args.hostname`.

"""
def cvt_joint_mask(value):
"""
Converts an input value to an integer and checks if it falls within a
specified range of 0 to 6. If the value is valid, it returns the corresponding
integer; otherwise, it raises an error with a descriptive message.

Args:
value (Union[int, str]): Required as an argument when this function
is called from the command line using argparse. It represents a
joint mask value to be converted.

Returns:
int: A representation of the joint position within a predefined range
of [0, 7) if it falls within this range. Otherwise, it raises an error.
The returned integer corresponds to one of seven possible positions.

"""
int_value = int(value)
if 0 <= int_value < 7:
return int_value
Expand Down Expand Up @@ -112,6 +216,16 @@ def cvt_joint_mask(value):


def main():
"""
Initializes and controls a robot client application, allowing it to connect
to a KUKA Sunrise controller and perform an LBR Joint Sine Overlay test while
collecting data for analysis and plotting after successful completion.

Returns:
int: 0 if the program completes normally and 1 if a connection to the KUKA
Sunrise controller fails.

"""
print("Running FRI Version:", fri.FRI_CLIENT_VERSION)

args = args_factory()
Expand Down
106 changes: 106 additions & 0 deletions examples/LBRTorqueSineOverlay.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,49 @@


class LBRTorqueSineOverlayClient(fri.LBRClient):
"""
Monitors and controls a robot arm by applying sinusoidal torques to specific
joints, synchronized with the robot's sampling frequency. It updates torque
values based on the current phase of the sine wave and sends these commands
to the robot.

Attributes:
joint_mask (numpyndarray|int): Used to specify a subset of joints on which
the torque overlay should be applied. It filters the joints for which
the torques will be calculated.
freq_hz (float): Used to represent a frequency value in Hertz. It appears
to be used as a factor for generating sinusoidal torques in the robot's
joints.
torque_ampl (float): Initialized during object creation with a value
specified by the user, representing the amplitude of the torque signal
to be applied to the joints.
phi (float): Initialized to zero. It represents a phase variable used for
generating sine wave offsets applied to joint torques during
torque-controlled operations.
step_width (float): 0 by default. It is set to a value that represents the
step width for the sine wave function, calculated as twice pi times
the frequency in Hz times the sample time of the robot state.
torques (npndarray[float32]): Initialized as a NumPy array with zeros. It
stores the torques to be applied to specific joints based on a sine
wave pattern.

"""
def __init__(self, joint_mask, freq_hz, torque_amplitude):
"""
Initializes the object's attributes: joint mask, frequency, torque amplitude,
and state variables (phi, step width, and torques) with default values or
those provided as arguments. It also calls the parent class's `__init__`
method using super().

Args:
joint_mask (numpy.ndarray | List[bool]): 1D array-like object containing
boolean values, where each value corresponds to a joint and indicates
whether it should be included or excluded from the simulation.
freq_hz (float): Used to specify the frequency in Hertz of the torques
applied by the system.
torque_amplitude (float): 3 times larger than `freq_hz`.

"""
super().__init__()
self.joint_mask = joint_mask
self.freq_hz = freq_hz
Expand All @@ -21,6 +63,21 @@ def monitor(self):
pass

def onStateChange(self, old_state, new_state):
"""
Monitors state changes and resets internal variables when transitioning
to the MONITORING_READY state. It initializes torques, phase angle, and
step width based on the robot's sample time and frequency.

Args:
old_state (fri.ESessionState): Used to record the state of the session
before the current change, which is then printed by the function
as it changes.
new_state (Union[fri.ESessionState, str]): Not fully specified in this
code snippet, indicating that it may contain different values from
the fri.ESessionState enum, which represents various states in the
robotics session.

"""
print(f"State changed from {old_state} to {new_state}")

if new_state == fri.ESessionState.MONITORING_READY:
Expand All @@ -31,12 +88,24 @@ def onStateChange(self, old_state, new_state):
)

def waitForCommand(self):
"""
Sets joint positions and torques based on current state before sending new
commands to the robot, ensuring a smooth transition between commands when
client command mode is torque control.

"""
self.robotCommand().setJointPosition(self.robotState().getIpoJointPosition())

if self.robotState().getClientCommandMode() == fri.EClientCommandMode.TORQUE:
self.robotCommand().setTorque(self.torques)

def command(self):
"""
Sends torque commands to a robot, applying a sine wave pattern to selected
joints. It updates joint positions and torques based on the current client
command mode and phase of the sine wave.

"""
self.robotCommand().setJointPosition(self.robotState().getIpoJointPosition())

if self.robotState().getClientCommandMode() == fri.EClientCommandMode.TORQUE:
Expand All @@ -52,7 +121,34 @@ def command(self):


def args_factory():
"""
Initializes an argument parser for a command-line interface, validating user
input and converting it into a format suitable for further processing by a
KUKA Sunrise Controller. It returns parsed arguments as namespace objects.

Returns:
argparseNamespace: A container object that stores all arguments passed to
it, along with their default values if provided. It encapsulates all parsed
command-line arguments into a structured format for further processing and
use within the application.

"""
def cvt_joint_mask(value):
"""
Converts a given value to an integer within the range 0 to 6 and returns
it if valid. It checks for values outside this range, raising an error
with an informative message if encountered.

Args:
value (Union[int, str]): Implicitly defined by argparse which typically
expects it to be a string that represents an integer.

Returns:
int|None: An integer value within the range from 0 to 6 (inclusive),
if the input is valid; otherwise, it raises a TypeError with a message
describing the invalid input.

"""
int_value = int(value)
if 0 <= int_value < 7:
return int_value
Expand Down Expand Up @@ -99,6 +195,16 @@ def cvt_joint_mask(value):


def main():
"""
Initializes a KUKA Sunrise controller client, connects to it, and enters a
loop where it steps the application until the session state becomes idle or a
keyboard interrupt occurs.

Returns:
int: 1 if a connection to KUKA Sunrise controller fails, and 0 otherwise,
indicating successful execution.

"""
print("Running FRI Version:", fri.FRI_CLIENT_VERSION)

args = args_factory()
Expand Down
Loading
Loading