PointAxisTarget
- class compas_fab.robots.PointAxisTarget[source]
Bases:
Target
Represents a point and axis target for the robot’s end-effector motion planning.
This target allows one degree of rotational freedom, enabling the end-effector to rotate around the target axis. Given a PointAxisTarget, the planner seeks a path to move the robot’s end-effector tool tip to the target point and align the tool tip’s Z axis with the specified target axis.
PointAxisTarget is suitable for tasks like drilling, milling, and 3D printing, where aligning the end-effector with a target axis is crucial, but the orientation around the axis is not important. Note that PointAxisTarget only represents a single target, for a sequence of targets, consider using
PointAxisWaypoints
.The user must define (1) the target point of which the tool tip will reach and (2) the target axis where the tool tip coordinate frame (TCF)’s Z axis can rotate around. The target point and axis are defined relative to the robot’s world coordinate frame (WCF).
In addition, it’s necessary to define the tool tip coordinate frame (TCF) relative to the robot’s flange frame. This is labeled as tool_coordinate_frame. If tool_coordinate_frame is unspecified, the target point and axis will be matched with the robot’s flange frame.
For robots with multiple end effector attachment points, the FCF depends on the planning group setting in the planning request, as defined in an SRDF file or
compas_fab.robots.RobotSemantics
.- Attributes:
- target_point
compas.geometry.Point
The target point defined relative to the world coordinate frame (WCF).
- target_z_axis
compas.geometry.Vector
The target axis is defined by the target_point and pointing towards this vector. A unitized vector is recommended. The tool tip coordinate frame (TCF)’s Z axis can rotate around this axis.
- tolerance_positionfloat, optional
The tolerance for the position of the target point. If not specified, the default value from the planner is used.
- tool_coordinate_frame
compas.geometry.Frame
, optional The tool tip coordinate frame relative to the flange coordinate frame of the robot. If not specified, the target point is relative to the robot’s flange (T0CF) and the Z axis of the flange can rotate around the target axis.
- namestr, optional
The human-readable name of the target. Defaults to ‘Point-Axis Target’.
- target_point
Methods
Returns a copy of the target where the target point and tolerances are scaled.
Inherited Methods
Converts the instance to a string.
Make an independent copy of the data object.
Construct an object of this type from a JSON file.
Construct an object of this type from a JSON string.
Compute a hash of the data for comparison during version control using the sha256 algorithm.
Convert an object to its native data representation and save it to a JSON file.
Convert an object to its native data representation and save it to a JSON string.
Validate the data against the object's data schema.