Skip to content
Merged
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
10 changes: 5 additions & 5 deletions examples/ex_allow_collisions.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand All @@ -38,10 +38,10 @@ def main():
# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)

Expand Down
11 changes: 6 additions & 5 deletions examples/ex_clear_planning_scene.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand All @@ -42,13 +42,14 @@ def main():
# Create callback group that allows execution of callbacks in parallel without restrictions
callback_group = ReentrantCallbackGroup()


# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)

Expand Down
10 changes: 5 additions & 5 deletions examples/ex_collision_mesh.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot

DEFAULT_EXAMPLE_MESH = path.join(
path.dirname(path.realpath(__file__)), "assets", "suzanne.stl"
Expand Down Expand Up @@ -50,10 +50,10 @@ def main():
# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)

Expand Down
10 changes: 5 additions & 5 deletions examples/ex_collision_primitive.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand Down Expand Up @@ -42,10 +42,10 @@ def main():
# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)

Expand Down
10 changes: 5 additions & 5 deletions examples/ex_fk.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2, MoveIt2State
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand Down Expand Up @@ -42,10 +42,10 @@ def main():
# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)

Expand Down
10 changes: 5 additions & 5 deletions examples/ex_gripper.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
from rclpy.node import Node

from pymoveit2 import GripperInterface
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand All @@ -34,10 +34,10 @@ def main():
# Create gripper interface
gripper_interface = GripperInterface(
node=node,
gripper_joint_names=panda.gripper_joint_names(),
open_gripper_joint_positions=panda.OPEN_GRIPPER_JOINT_POSITIONS,
closed_gripper_joint_positions=panda.CLOSED_GRIPPER_JOINT_POSITIONS,
gripper_group_name=panda.MOVE_GROUP_GRIPPER,
gripper_joint_names=robot.gripper_joint_names(),
open_gripper_joint_positions=robot.OPEN_GRIPPER_JOINT_POSITIONS,
closed_gripper_joint_positions=robot.CLOSED_GRIPPER_JOINT_POSITIONS,
gripper_group_name=robot.MOVE_GROUP_GRIPPER,
callback_group=callback_group,
gripper_command_action_name="gripper_action_controller/gripper_cmd",
)
Expand Down
10 changes: 5 additions & 5 deletions examples/ex_ik.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2, MoveIt2State
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand All @@ -32,10 +32,10 @@ def main():
# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)

Expand Down
11 changes: 5 additions & 6 deletions examples/ex_joint_goal.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2, MoveIt2State
from pymoveit2.robots import panda

from pymoveit2.robots import panda as robot

def main():
rclpy.init()
Expand Down Expand Up @@ -47,10 +46,10 @@ def main():
# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)
moveit2.planner_id = (
Expand Down
10 changes: 5 additions & 5 deletions examples/ex_orientation_path_constraint.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2, MoveIt2State
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand Down Expand Up @@ -64,10 +64,10 @@ def main():
# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)

Expand Down
10 changes: 5 additions & 5 deletions examples/ex_pose_goal.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2, MoveIt2State
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand Down Expand Up @@ -43,10 +43,10 @@ def main():
# Create MoveIt 2 interface
moveit2 = MoveIt2(
node=node,
joint_names=panda.joint_names(),
base_link_name=panda.base_link_name(),
end_effector_name=panda.end_effector_name(),
group_name=panda.MOVE_GROUP_ARM,
joint_names=robot.joint_names(),
base_link_name=robot.base_link_name(),
end_effector_name=robot.end_effector_name(),
group_name=robot.MOVE_GROUP_ARM,
callback_group=callback_group,
)
moveit2.planner_id = (
Expand Down
4 changes: 2 additions & 2 deletions examples/ex_servo.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
from rclpy.node import Node

from pymoveit2 import MoveIt2Servo
from pymoveit2.robots import panda
from pymoveit2.robots import panda as robot


def main():
Expand All @@ -27,7 +27,7 @@ def main():
# Create MoveIt 2 Servo interface
moveit2_servo = MoveIt2Servo(
node=node,
frame_id=panda.base_link_name(),
frame_id=robot.base_link_name(),
callback_group=callback_group,
)

Expand Down
34 changes: 34 additions & 0 deletions pymoveit2/robots/ur.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
from typing import List

MOVE_GROUP_ARM: str = "ur_manipulator"
MOVE_GROUP_GRIPPER: str = "gripper"

prefix: str = ""

OPEN_GRIPPER_JOINT_POSITIONS: List[float] = [0.04, 0.04]
CLOSED_GRIPPER_JOINT_POSITIONS: List[float] = [0.0, 0.0]


def joint_names(prefix: str = prefix) -> List[str]:
return [
prefix + "shoulder_pan_joint",
prefix + "shoulder_lift_joint",
prefix + "elbow_joint",
prefix + "wrist_1_joint",
prefix + "wrist_2_joint",
prefix + "wrist_3_joint",
]


def base_link_name(prefix: str = prefix) -> str:
return prefix + "base_link"


def end_effector_name(prefix: str = prefix) -> str:
return prefix + "tool0"


def gripper_joint_names(prefix: str = prefix) -> List[str]:
return [

]