Skip to content

Commit

Permalink
fixing tests
Browse files Browse the repository at this point in the history
  • Loading branch information
yck011522 committed Oct 21, 2024
1 parent a14983d commit e656a5f
Show file tree
Hide file tree
Showing 15 changed files with 67 additions and 51 deletions.
2 changes: 1 addition & 1 deletion src/compas_fab/backends/interfaces/backend_features.py
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ def _build_configuration(
robot_cell = self.client.robot_cell # type: RobotCell
if return_full_configuration:
# build configuration including passive joints, but no sorting
configuration = robot_cell.zero_configuration()
configuration = robot_cell.zero_full_configuration()
value_dict = dict(zip(joint_names, joint_positions))
for name in configuration.joint_names:
if name in value_dict:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,9 @@ def forward_kinematics(self, robot_cell_state, target_mode, scale=None, group=No
joint_values = robot_cell_state.robot_configuration.joint_values
pcf_frame = planner.kinematics_solver.forward(joint_values)

target_frame = robot_cell.pcf_to_target_frames(robot_cell_state, pcf_frame, target_mode, group)
target_frame = robot_cell.pcf_to_target_frames(
robot_cell_state, pcf_frame, target_mode, robot_cell.main_group_name
)

# Scale the frame to user units
if scale:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,13 +75,14 @@ def iter_inverse_kinematics_frame_target(self, target, start_state=None, group=N
This function handles the case where the target is a :class:`compas_fab.robots.FrameTarget`.
"""
planner = self # type: AnalyticalKinematicsPlanner
robot_cell = planner.client.robot_cell # type: RobotCell

# Scale Target and get target frame
target = target.normalized_to_meters()
target_frame = target.target_frame

target_frame = planner.client.robot_cell.target_frames_to_pcf(
start_state, target_frame, target.target_mode, group=group
start_state, target_frame, target.target_mode, group=robot_cell.main_group_name
)

return self.inverse_kinematics_ordered(target_frame, group=group, options=options)
Expand Down
4 changes: 0 additions & 4 deletions src/compas_fab/backends/kinematics/planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -68,10 +68,6 @@ def __init__(self, kinematics_solver, verbose=False):
# The AnalyticalKinematicsPlanner does not require the user to know about the underlying client
# therefore the following properties are provided to access the client's properties

@property
def robot(self):
return self._client.robot_cell.robot

@property
def robot_cell(self):
return self._client.robot_cell
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,8 +145,8 @@ def verbose_print(msg):
collision_messages.append(cc_pair_info + " - COLLISION")
collision_pairs.append(
(
client.robot_cell.robot_model.get_link_by_name(link_1_name),
client.robot_cell.robot_model.get_link_by_name(link_2_name),
robot_cell.robot_model.get_link_by_name(link_1_name),
robot_cell.robot_model.get_link_by_name(link_2_name),
)
)
if not full_report: # Fail on first error if full_report is not requested
Expand Down Expand Up @@ -178,8 +178,8 @@ def verbose_print(msg):
collision_messages.append(cc_pair_info + " - COLLISION")
collision_pairs.append(
(
client.robot_cell.robot_model.get_link_by_name(link_name),
client.robot_cell.tool_models[tool_name],
robot_cell.robot_model.get_link_by_name(link_name),
robot_cell.tool_models[tool_name],
)
)
if not full_report: # Fail on first error if full_report is not requested
Expand Down Expand Up @@ -211,8 +211,8 @@ def verbose_print(msg):
collision_messages.append(cc_pair_info + " (body_id '{}') - COLLISION".format(body_id))
collision_pairs.append(
(
client.robot_cell.robot_model.get_link_by_name(link_name),
client.robot_cell.rigid_body_models[body_name],
robot_cell.robot_model.get_link_by_name(link_name),
robot_cell.rigid_body_models[body_name],
)
)
if not full_report: # Fail on first error if full_report is not requested
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -314,7 +314,7 @@ def iter_inverse_kinematics_frame_target(self, target, robot_cell_state, group,
# The order of the values needs to match with pybullet's joint id order
# Start configuration needs to be a full_configuration, not negotiable.
start_configuration = robot_cell_state.robot_configuration
all_joint_names = robot_cell.get_configurable_joint_names()
all_joint_names = robot_cell.robot_model.get_configurable_joint_names()
assert set(all_joint_names) == set(start_configuration.keys()), "Robot configuration is missing some joints"
rest_poses = client.build_pose_for_pybullet(start_configuration)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,10 +94,9 @@ def set_robot_cell_state(self, robot_cell_state):
if not robot_cell_state.robot_configuration:
continue
# If tool is attached to a group, update the tool's base frame using the group's FK frame
link_name = client.robot.get_link_names(tool_state.attached_to_group)[-1]
link_name = client.robot_cell.get_link_names(tool_state.attached_to_group)[-1]
robot_configuration = robot_cell_state.robot_configuration
# Get PCF of the Robot
# planner_coordinate_frame = client.robot.model.forward_kinematics(robot_configuration, link_name)
pcf_link_id = client.robot_link_puids[link_name]
planner_coordinate_frame = client._get_link_frame(pcf_link_id, client.robot_puid)
tool_base_frame = self._compute_tool_base_frame_from_planner_coordinate_frame(
Expand Down Expand Up @@ -140,7 +139,7 @@ def set_robot_cell_state(self, robot_cell_state):
# If rigid body is attached to a link, update the rigid body's base frame using the link's FK frame
link_name = rigid_body_state.attached_to_link
robot_configuration = robot_cell_state.robot_configuration
link_frame = client.robot.model.forward_kinematics(robot_configuration, link_name)
link_frame = client.robot_model.forward_kinematics(robot_configuration, link_name)
attachment_frame = rigid_body_state.attachment_frame

# Compute the RB position with its attachment frame relative to the link frame
Expand Down
3 changes: 0 additions & 3 deletions src/compas_fab/robots/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
Robot
RobotSemantics
Tool
Duration
Wrench
Inertia
Expand Down Expand Up @@ -196,8 +195,6 @@
"Waypoints",
# Time
"Duration",
# Tool
"Tool",
# Trajectory
"JointTrajectory",
"JointTrajectoryPoint",
Expand Down
1 change: 0 additions & 1 deletion src/compas_fab/robots/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@
from compas_fab.robots import JointTrajectory # noqa: F401
from compas_fab.robots import RobotSemantics # noqa: F401
from compas_fab.robots import Target # noqa: F401
from compas_fab.robots import Tool # noqa: F401
from compas_fab.robots import Waypoints # noqa: F401


Expand Down
5 changes: 5 additions & 0 deletions src/compas_fab/robots/robot_cell.py
Original file line number Diff line number Diff line change
Expand Up @@ -439,6 +439,9 @@ def get_configurable_joints(self, group=None):
i.e., not ``Joint.FIXED``, not mimicking another joint and not a passive joint.
See :meth:`compas_robots.model.Joint.is_configurable` for more details.
Important: Setting the `group` to None, does not return all configurable joints of the robot.
If all configurable joints of the robot are needed, use :meth:`RobotModel.get_configurable_joints()`.
Parameters
----------
group : :obj:`str`, optional
Expand All @@ -465,6 +468,8 @@ def get_configurable_joint_names(self, group=None):
Similar to :meth:`get_configurable_joints` but returning joint names.
If all configurable joints of the robot are needed, use :meth:`RobotModel.get_configurable_joint_names()`.
Parameters
----------
group : :obj:`str`, optional
Expand Down
41 changes: 26 additions & 15 deletions tests/api/compas_fab_api.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"metadata": {
"compas_fab_version": "1.0.2",
"generated_on": "20240503"
"generated_on": "20241021"
},
"modules": {
"compas_fab": [
Expand All @@ -10,18 +10,31 @@
"compas_fab.backends": [
"ABB_IRB4600_40_255Kinematics",
"AnalyticalInverseKinematics",
"AnalyticalKinematicsPlanner",
"AnalyticalPlanCartesianMotion",
"AnalyticalPyBulletClient",
"AnalyticalPyBulletPlanner",
"BackendError",
"BackendFeatureNotSupportedError",
"BackendTargetNotSupportedError",
"CancellableFutureResult",
"CartesianMotionError",
"CollisionError",
"CollisionCheckError",
"FutureResult",
"InverseKinematicsError",
"KinematicsError",
"MPInterpolationInCollisionError",
"MPMaxJumpError",
"MPNoIKSolutionError",
"MPNoPlanFoundError",
"MPSearchTimeOutError",
"MPStartStateInCollisionError",
"MPTargetInCollisionError",
"MotionPlanningError",
"MoveItPlanner",
"OffsetWristKinematics",
"PlanningGroupNotExistsError",
"PlanningGroupNotSupported",
"PyBulletClient",
"PyBulletError",
"PyBulletPlanner",
Expand All @@ -31,6 +44,7 @@
"RosValidationError",
"SphericalWristKinematics",
"Staubli_TX260LKinematics",
"TargetModeMismatchError",
"UR10Kinematics",
"UR10eKinematics",
"UR3Kinematics",
Expand All @@ -39,9 +53,7 @@
"UR5eKinematics"
],
"compas_fab.robots": [
"AttachedCollisionMesh",
"BoundingVolume",
"CollisionMesh",
"ConfigurationTarget",
"Constraint",
"ConstraintSetTarget",
Expand All @@ -55,16 +67,21 @@
"JointTrajectoryPoint",
"OrientationConstraint",
"OrthonormalVectorsFromAxisGenerator",
"PlanningScene",
"PointAxisTarget",
"PointAxisWaypoints",
"PositionConstraint",
"ReachabilityMap",
"Robot",
"RobotLibrary",
"RigidBody",
"RigidBodyLibrary",
"RigidBodyState",
"RobotCell",
"RobotCellLibrary",
"RobotCellState",
"RobotSemantics",
"Target",
"Tool",
"TargetMode",
"ToolLibrary",
"ToolState",
"Trajectory",
"Waypoints",
"Wrench",
Expand All @@ -87,16 +104,10 @@
"argsort",
"clamp",
"diffs",
"from_tcf_to_t0cf",
"list_files_in_directory",
"map_range",
"range_geometric_row",
"read_csv_to_dictionary",
"read_data_from_json",
"read_data_from_pickle",
"sign",
"write_data_to_json",
"write_data_to_pickle"
"sign"
]
}
}
16 changes: 8 additions & 8 deletions tests/backends/pybullet/test_pybullet_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ def test_pybullet_client_set_robot():
# Check that the RobotModel is present
assert isinstance(robot_cell.robot_model, RobotModel)
assert isinstance(robot_cell.robot_semantics, RobotSemantics)
assert robot_cell.name == "ur5_robot"
assert robot_cell.robot_model.name == "ur5_robot"
# Check that the robot have geometry
robot_cell.ensure_geometry()

Expand All @@ -55,18 +55,18 @@ def test_pybullet_client_set_all_robots_from_robot_library():
# Testing workflow of using robot from RobotCellLibrary
with PyBulletClient(connection_type="direct") as client:

def set_and_check_robot_cell(robot_cell):
def set_and_check_robot_cell(robot_cell, robot_cell_state):
client.set_robot(robot_cell.robot_model, robot_cell.robot_semantics)
assert isinstance(robot_cell.robot_model, RobotModel)
assert isinstance(robot_cell.robot_semantics, RobotSemantics)
client.remove_robot()

set_and_check_robot_cell(RobotCellLibrary.ur5())
set_and_check_robot_cell(RobotCellLibrary.ur10e())
set_and_check_robot_cell(RobotCellLibrary.panda())
set_and_check_robot_cell(RobotCellLibrary.abb_irb120_3_58())
set_and_check_robot_cell(RobotCellLibrary.abb_irb4600_40_255())
set_and_check_robot_cell(RobotCellLibrary.rfl())
set_and_check_robot_cell(*RobotCellLibrary.ur5())
set_and_check_robot_cell(*RobotCellLibrary.ur10e())
set_and_check_robot_cell(*RobotCellLibrary.panda())
set_and_check_robot_cell(*RobotCellLibrary.abb_irb120_3_58())
set_and_check_robot_cell(*RobotCellLibrary.abb_irb4600_40_255())
set_and_check_robot_cell(*RobotCellLibrary.rfl())


def test_pybullet_client_set_robot_configuration():
Expand Down
2 changes: 1 addition & 1 deletion tests/backends/pybullet/test_pybullet_planner_fk_ik.py
Original file line number Diff line number Diff line change
Expand Up @@ -436,7 +436,7 @@ def test_ik_modified_only_joints_in_group(pybullet_client):

planner = PyBulletPlanner(pybullet_client)
planner.set_robot_cell(robot_cell)
initial_configuration = robot_cell.zero_configuration()
initial_configuration = robot_cell.zero_full_configuration()
initial_configuration["panda_joint1"] = 0.123
initial_configuration["panda_joint7"] = 0.123
print(initial_configuration)
Expand Down
10 changes: 7 additions & 3 deletions tests/robots/test_robot_cell.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
import pytest

from compas_fab.robots import RobotCellLibrary
from compas_fab.robots import RobotCell # noqa: F401
from compas_fab.robots import RobotCellState # noqa: F401


@pytest.fixture
Expand All @@ -24,8 +26,9 @@ def test_robot_cell_copy(ur10e_gripper_one_beam, abb_irb4600_40_255_gripper_one_
"""Test to comply with Data.copy() mechanism"""

def test(robot_cell, robot_cell_state):
robot_cell_copy = robot_cell.copy()
assert robot_cell.robot.name == robot_cell_copy.robot.name
# type: (RobotCell, RobotCellState) -> None
robot_cell_copy = robot_cell.copy() # type: RobotCell
assert robot_cell.robot_model.name == robot_cell_copy.robot_model.name
assert robot_cell.tool_ids == robot_cell_copy.tool_ids
assert robot_cell.rigid_body_ids == robot_cell_copy.rigid_body_ids

Expand All @@ -44,9 +47,10 @@ def test_robot_cell_deepcopy(
"""Test to make sure copy.deepcopy works"""

def test(robot_cell, robot_cell_state):
# type: (RobotCell, RobotCellState) -> None

robot_cell_copy = deepcopy(robot_cell)
assert robot_cell.robot.name == robot_cell_copy.robot.name
assert robot_cell.robot_model.name == robot_cell_copy.robot_model.name
assert robot_cell.tool_ids == robot_cell_copy.tool_ids
assert robot_cell.rigid_body_ids == robot_cell_copy.rigid_body_ids

Expand Down
8 changes: 5 additions & 3 deletions tests/robots/test_semantics.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import pytest
from compas_robots import RobotModel

from compas_fab.robots import RobotCell
from compas_fab.robots import RobotSemantics
from compas_fab.robots import RobotCellLibrary

Expand All @@ -22,11 +23,12 @@ def panda_urdf():
def test_panda_srdf_file(panda_srdf, panda_urdf):
model = RobotModel.from_urdf_file(panda_urdf)
semantics = RobotSemantics.from_srdf_file(panda_srdf, model)
robot_cell = RobotCell(model, semantics)
assert sorted(semantics.group_names) == sorted(["panda_arm", "hand", "panda_arm_hand"])
assert semantics.main_group_name == "panda_arm_hand"
assert semantics.get_base_link_name("panda_arm") == "panda_link0"
assert semantics.get_end_effector_link_name("panda_arm") == "panda_link8"
assert semantics.get_configurable_joint_names(model, "panda_arm") == [
assert robot_cell.get_configurable_joint_names("panda_arm") == [
"panda_joint1",
"panda_joint2",
"panda_joint3",
Expand All @@ -35,7 +37,7 @@ def test_panda_srdf_file(panda_srdf, panda_urdf):
"panda_joint6",
"panda_joint7",
]
all_configurable_joint_names = [j.name for j in semantics.get_all_configurable_joints(model)]
all_configurable_joint_names = [j.name for j in robot_cell.get_all_configurable_joints()]
assert all_configurable_joint_names == [
"panda_joint1",
"panda_joint2",
Expand All @@ -46,7 +48,7 @@ def test_panda_srdf_file(panda_srdf, panda_urdf):
"panda_joint7",
"panda_finger_joint1",
]
configurable_joints = semantics.get_configurable_joints(model, "panda_arm_hand")
configurable_joints = robot_cell.get_configurable_joints("panda_arm_hand")
assert [j.type for j in configurable_joints] == [0, 0, 0, 0, 0, 0, 0, 2]
set_joints = set(semantics.group_states["panda_arm"]["ready"].keys())
assert set_joints == {
Expand Down

0 comments on commit e656a5f

Please sign in to comment.