Skip to content
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -244,13 +244,18 @@ class Arm(Platform):
gripper (bool): Whether the arm has a gripper attached.
moveit (bool) : Whether to enable MoveIt motion planning.
ip_address (str): IP address of the arm controller.
controller (Literal["fr3_arm_controller", "demo_controller"]): Arm controller to run.
moveit_config (MoveitConfig): MoveIt configuration settings.
"""

platform_type: str = "Arm"
gripper: bool = False
moveit: bool = False
ip_address: str = "10.15.20.4"
controller: Literal[
"fr3_arm_controller",
"demo_controller",
] = "fr3_arm_controller"

moveit_config: MoveitConfig = field(default_factory=MoveitConfig)

Expand Down
7 changes: 7 additions & 0 deletions alliander_franka/src/alliander_franka/config/controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@
fr3_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController

demo_controller:
type: franka_example_controllers/CartesianVelocityExampleController

fr3_arm_controller:
ros__parameters:
type: joint_trajectory_controller/JointTrajectoryController
Expand Down Expand Up @@ -61,3 +64,7 @@
fr3_joint7:
goal: 0.01
trajectory: 0.1

demo_controller:
ros__parameters:
robot_type: "fr3"
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,11 @@ def launch_setup(context: LaunchContext) -> list:
namespace=arm_config.namespace,
)

fr3_arm_controller_spawner = Node(
arm_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=[
"fr3_arm_controller",
f"{arm_config.controller}",
"--switch-timeout",
str(TIMEOUT),
],
Expand Down Expand Up @@ -80,7 +80,7 @@ def launch_setup(context: LaunchContext) -> list:

return [
Register.on_exit(joint_state_broadcaster_spawner, context),
Register.on_exit(fr3_arm_controller_spawner, context),
Register.on_exit(arm_controller_spawner, context),
Register.on_start(fr3_gripper, context),
(
Register.on_exit(gripper_action_controller_spawner, context)
Expand Down
19 changes: 17 additions & 2 deletions predefined_configurations.py
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,7 @@ def config_lynx_ouster(self) -> None: # noqa: D102
@register_configuration("mm")
def config_mm(self) -> None: # noqa: D102
vehicle = Vehicle("panther", (0, 0, 0.2))
arm = Arm("franka", (0, 0, 0.14), gripper=True, moveit=True)
arm = Arm("franka", (0.20, 0, 0.20), gripper=True, moveit=True)

link(vehicle, arm)
self.plat_conf.platforms = [vehicle, arm]
Expand All @@ -249,7 +249,7 @@ def config_mm(self) -> None: # noqa: D102
def config_mm_velodyne(self) -> None: # noqa: D102
vehicle = Vehicle("panther", (0, 0, 0.2))
vehicle.nav2_config.navigation = True
arm = Arm("franka", (0, 0, 0.14), gripper=True, moveit=True)
arm = Arm("franka", (0.20, 0, 0.20), gripper=True, moveit=True)
lidar = Lidar("velodyne", (0.13, -0.13, 0.35))

link(vehicle, arm)
Expand All @@ -262,3 +262,18 @@ def config_panther_and_franka(self) -> None: # noqa: D102
vehicle = Vehicle("panther", (0, -0.5, 0.2))
arm = Arm("franka", (0, 0.5, 0))
self.plat_conf.platforms = [vehicle, arm]

# Demo configurations:
@register_configuration("demo_panther_franka")
def config_demo_panther_franka(self) -> None: # noqa: D102
vehicle = Vehicle("panther", (0, 0, 0.2))
arm = Arm(
"franka",
(0.20, 0, 0.20),
gripper=True,
moveit=True,
controller="demo_controller",
)

link(vehicle, arm)
self.plat_conf.platforms = [vehicle, arm]