SimpleHexapod#
- class lsst.ts.mthexapod.SimpleHexapod(base_positions, mirror_positions, pivot, min_length, max_length, speed)#
Bases:
objectSimple model of a hexapod: 6 linear actuators in an arbitrary arrangement.
The intent is to support the mock hexapod controller; as such this model is somewhat simplistic. The actuators ends are assumed to be perfect point flexures. It is not (yet) possible to compute orientation given actuator lengths.
See
make_zigzag_modelto make a standard symmetrical zigzag hexapod.- Parameters:
base_positions (
list[numpy.ndarray]) – Position of the base end of each linear actuator, as a list of z,y,z tuples, one per actuator.mirror_positions (
list[numpy.ndarray]) – Position of the mirror end of each actuator at zero orientation, as a list of z,y,z tuples, one per actuator.pivot (
tuple) – The point whose orientation is set by themovecommand. For a mirror it will typically be the vertex of the mirror.min_length (
float) – Mininum actuator length.max_length (
float) – Maximum actuator length.speed (
float) – Actuator speed.
Methods Summary
assert_in_range(actuator_lengths)Assert that all actuators would be in range if set to the specified length.
forward_kinematics(initial_guess, ...[, tol])Forward kinematics for a hexapod movement.
inverse_kinematics(positions, pivot, ...)Inverse kinematics for a hexapod movement.
make_zigzag_model(base_radius, ...)Make a
SimpleHexapodof a typical hexapod with 6 actuators in a symmetrical zigzag arrangement.move(pos, xyzrot)Move the actuators so the pivot point is at the specified orientation.
moving([tai])Is any actuator moving?
remaining_time([tai])Remaining time for this move (sec).
stop()Stop all actuators.
Methods Documentation
- assert_in_range(actuator_lengths)#
Assert that all actuators would be in range if set to the specified length.
- static forward_kinematics(initial_guess, strut_length_delta, pivot, mirror_positions, base_positions, tol=1e-06)#
Forward kinematics for a hexapod movement. This calculates the hexapod positions based on the delta strut lengths.
Notes
The calculation is translated from ts_mt_hexRot_simulink repository: hexapod_controller_source_final/hexapod_kin_calc.slx
- Parameters:
initial_guess (
numpy.ndarray) – Initial guess of the hexapod positions: (x, y, z, rx, ry, rz). The units are the meter and radian.strut_length_delta (
numpy.ndarray) – 6 delta strut lengths in meter.pivot (
numpy.ndarray) – Pivot (x, y, z) as the rotation center. The unit is meter.mirror_positions (
numpy.ndarray) – Strut positions on the mirror. This is a 3x6 matrix. The row is the (x, y, z) position in meter. The column is the strut index.base_positions (
numpy.ndarray) – Strut positions on the base. This is a 3x6 matrix. The row is the (x, y, z) position in meter. The column is the strut index.tol (
float, optional) – Tolerance for the optimization. (the default is 1e-6)
- Returns:
Estimated hexapod positions: (x, y, z, rx, ry, rz). The units are the meter and radian.
- Return type:
numpy.ndarray
- static inverse_kinematics(positions, pivot, mirror_positions, base_positions)#
Inverse kinematics for a hexapod movement. This calculates the delta strut lengths based on the hexapod positions.
Notes
The calculation is translated from ts_mt_hexRot_simulink repository: hexapod_controller_source_final/hexapod_kin_calc.slx
- Parameters:
positions (
numpy.ndarray) – Hexapod positions: (x, y, z, rx, ry, rz). The units are the meter and radian.pivot (
numpy.ndarray) – Pivot (x, y, z) as the rotation center. The unit is meter.mirror_positions (
numpy.ndarray) – Strut positions on the mirror. This is a 3x6 matrix. The row is the (x, y, z) position in meter. The column is the strut index.base_positions (
numpy.ndarray) – Strut positions on the base. This is a 3x6 matrix. The row is the (x, y, z) position in meter. The column is the strut index.
- Returns:
6 delta strut lengths in meter.
- Return type:
numpy.ndarray
- classmethod make_zigzag_model(base_radius, mirror_radius, mirror_z, base_angle0, pivot, min_length, max_length, speed)#
Make a
SimpleHexapodof a typical hexapod with 6 actuators in a symmetrical zigzag arrangement.The base ends of the 6 actuators terminate at 3 points at
z=0evenly distributed about a circle of radiusbase_radius: actuators 0 and 5 terminate at base_angle0, actuators 1 and 2 terminate at base_angle0 + 120, and actuators 3 and 4 terminate at base_angle0 + 240. The mirror ends of the actuators are similarly arrayed, in a plane atz=mirror_zwith attachment points rotated 60 degrees from the base attachment points: actuators 0 and 1 terminate at base_angle0 + 60, etc. This makes a zigzag pattern that is circularly symmetric about the z axis.- base_radius
float Radius of base positions of actuators.
- mirror_radius
float Radius of mirror positions of actuators.
- mirror_z
float z distance between the base ends and the mirror ends of the linear actuators.
- base_angle0
float Angle of first base actuator point in x,y plane (deg).
- pivot
tuple The point whose orientation is set by the
movecommand. For a mirror it will typically be the vertex of the mirror.- min_length
float Mininum actuator length.
- max_length
float Maximum actuator length.
- speed
float Actuator speed.
- base_radius
- move(pos, xyzrot)#
Move the actuators so the pivot point is at the specified orientation.
- moving(tai=None)#
Is any actuator moving?
- remaining_time(tai=None)#
Remaining time for this move (sec).