def to_compas_rrc( self, ): # type: () -> Tuple[Callable, List[Union[Frame, compas_rrc.RobotJoints]]] if self.trajectory_type == self.FRAME_TRAJECTORY: rrc_trajectory = self._list rrc_instruction = compas_rrc.MoveToRobtarget if self.trajectory_type == self.JOINT_TRAJECTORY: rrc_trajectory = [ compas_rrc.RobotJoints(*to_degrees(pt.values)) for pt in self.points ] rrc_instruction = compas_rrc.MoveToJoints return rrc_instruction, rrc_trajectory
def revolute_configuration_to_robot_joints(configuration): """Convert a :class:`compas_fab.robots.Configuration` to a :class:`compas_rrc.RobotJoints`. This function ignores non revolute values. Parameter --------- configuration : :class:`Configuration` Returns ------- :class:`RobotJoints` """ # noqa: E501 revolute_values_in_degrees = to_degrees(configuration.revolute_values) return compas_rrc.RobotJoints(*revolute_values_in_degrees)
def test_robot_joints(): j = rrc.RobotJoints() assert list(j) == [] j = rrc.RobotJoints(30) assert list(j) == [30] j = rrc.RobotJoints(30, 10, 0) assert list(j) == [30, 10, 0] j = rrc.RobotJoints([30, 10, 0]) assert list(j) == [30, 10, 0] j = rrc.RobotJoints(iter([30, 10, 0])) assert list(j) == [30, 10, 0] j = rrc.RobotJoints(30, 45, 0) c = j.to_configuration_primitive([0, 1, 2], ['j1', 'j2', 'j3']) assert c.joint_values == [math.pi/6, math.pi/4, 0.0] assert c.joint_names == ['j1', 'j2', 'j3'] j = rrc.RobotJoints(30, -45, 100) c = j.to_configuration_primitive([0, 1, 2]) assert c.joint_values == [math.pi/6, -math.pi/4, 0.1] assert len(c.joint_names) == 0 config = Configuration([2*math.pi, math.pi, math.pi/2, math.pi/3, math.pi/4, math.pi/6], [0, 0, 0, 0, 0, 0]) rj = rrc.RobotJoints.from_configuration_primitive(config) assert allclose(rj.values, [360, 180, 90, 60, 45, 30]) config = Configuration( [0, 2*math.pi, math.pi, math.pi/2, math.pi/3, math.pi/4, math.pi/6 ], [0, 0, 0, 0, 0, 0, 0], ['a', 'b', 'c', 'd', 'e', 'f', 'g']) rj = rrc.RobotJoints.from_configuration_primitive(config, ['b', 'c', 'd', 'e', 'f', 'g']) assert allclose(rj.values, [360, 180, 90, 60, 45, 30]) j = rrc.RobotJoints(30, 10, 0) config = j.to_configuration_primitive([0, 0, 0]) new_j = rrc.RobotJoints.from_configuration_primitive(config) assert allclose(j.values, new_j.values)
def test_move_to_joints(): joints = [30, 90, 0, 0, 0] extaxe = [0, 0, 100] inst = rrc.MoveToJoints(joints, extaxe, 100, rrc.Zone.FINE) assert inst.float_values == [ 30, 90, 0, 0, 0, 0, 0, 0, 100, 0, 0, 0, 100, -1 ] assert not inst.string_values assert inst.exec_level == rrc.ExecutionLevel.ROBOT assert inst.feedback_level == rrc.FeedbackLevel.NONE joints = rrc.RobotJoints(30, 90, 0, 0, 0) extaxe = rrc.ExternalAxes(0, 0, 100) inst = rrc.MoveToJoints(joints, extaxe, 100, rrc.Zone.FINE) assert inst.float_values == [ 30, 90, 0, 0, 0, 0, 0, 0, 100, 0, 0, 0, 100, -1 ]