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
7 changes: 7 additions & 0 deletions rox_bringup/configs/franka/initial_positions.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
fr3_joint1: 1.5
fr3_joint2: -1.7
fr3_joint3: 2.5
fr3_joint4: -1.0
fr3_joint5: 1.5
fr3_joint6: 0.0
fr3_joint7: 0.0
38 changes: 38 additions & 0 deletions rox_bringup/configs/franka/simulation_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
/**:
controller_manager:
ros__parameters:
update_rate: 1000 # Hz
thread_priority: 98
enable_overrun: false

fr3_arm_controller:
type: joint_trajectory_controller/JointTrajectoryController

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

/**:
fr3_arm_controller:
ros__parameters:
command_interfaces:
- position
state_interfaces:
- position
- velocity
joints:
- fr3_joint1
- fr3_joint2
- fr3_joint3
- fr3_joint4
- fr3_joint5
- fr3_joint6
- fr3_joint7
gains:
fr3_joint1: { p: 600., d: 30., i: 0., i_clamp: 1. }
fr3_joint2: { p: 600., d: 30., i: 0., i_clamp: 1. }
fr3_joint3: { p: 600., d: 30., i: 0., i_clamp: 1. }
fr3_joint4: { p: 600., d: 30., i: 0., i_clamp: 1. }
fr3_joint5: { p: 250., d: 10., i: 0., i_clamp: 1. }
fr3_joint6: { p: 150., d: 10., i: 0., i_clamp: 1. }
fr3_joint7: { p: 50., d: 5., i: 0., i_clamp: 1. }

11 changes: 9 additions & 2 deletions rox_bringup/launch/bringup_sim_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,11 @@ def execution_stage(context: LaunchContext,
initial_joint_controller_name = 'arm_controller'
elif arm_typ in ['ur5', 'ur10', 'ur5e', 'ur10e']:
arm_manufacturer = 'ur'

elif arm_typ == 'fr3':
# new block for Franka FR3
arm_manufacturer = 'franka'
initial_joint_controller_name = 'fr3_arm_controller'

controllers_yaml = os.path.join(
get_package_share_directory('rox_bringup'),
'configs',
Expand Down Expand Up @@ -214,6 +218,9 @@ def execution_stage(context: LaunchContext,
env_var_value += ':' + os.path.dirname(get_package_share_directory('elite_description'))
elif arm_typ == 'ur5' or arm_typ == 'ur10' or arm_typ == 'ur5e' or arm_typ == 'ur10e':
env_var_value += ':' + os.path.dirname(get_package_share_directory('ur_description'))
elif arm_typ == 'fr3':
env_var_value += ':' + os.path.dirname(get_package_share_directory('franka_description'))

# Set environment variable for gripper description packages
# if gripper_typ == 'epick':
# env_var_value += ':' + os.path.dirname(get_package_share_directory('epick_description'))
Expand Down Expand Up @@ -265,7 +272,7 @@ def generate_launch_description():

declare_arm_type_cmd = DeclareLaunchArgument(
'arm_type', default_value='',
choices=['', 'ur5', 'ur10', 'ur5e', 'ur10e', 'ec66', 'cs66'],
choices=['', 'ur5', 'ur10', 'ur5e', 'ur10e', 'ec66', 'cs66','fr3'],
description='Arm Types\n\t'
)

Expand Down
2 changes: 1 addition & 1 deletion rox_description/launch/description_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ def generate_launch_description():

declare_arm_type_cmd = DeclareLaunchArgument(
'arm_type', default_value='',
choices=['', 'ur5', 'ur10', 'ur5e', 'ur10e', 'ec66', 'cs66'],
choices=['', 'ur5', 'ur10', 'ur5e', 'ur10e', 'ec66', 'cs66','fr3'],
description='Arm Types\n\t'
)

Expand Down
7 changes: 7 additions & 0 deletions rox_description/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,13 @@
<exec_depend>ur_robot_driver</exec_depend>
<exec_depend>ur_simulation_gz</exec_depend>

<!-- Dependencies for Franka Fr3 arm-->
<exec_depend>franka_description</exec_depend>
<exec_depend>franka_msgs</exec_depend>
<exec_depend>franka_gripper</exec_depend>
<exec_depend>franka_hw</exec_depend>
<exec_depend>franka_gazebo</exec_depend>

<!-- Dependencies for Realsense D435 -->
<exec_depend>realsense2_description</exec_depend>

Expand Down
8 changes: 8 additions & 0 deletions rox_description/urdf/rox.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,14 @@ Contributor: Adarsh Karan K P
<xacro:include filename="$(find rox_description)/urdf/xacros/elite_arm.urdf.xacro"/>
</xacro:if>

<!-- Franka Robotics Arms-->
<xacro:if value="${arm == 'fr3'}">
<xacro:property name="arm_height" value="0.276" />

<!-- Include the franka arm -->
<xacro:include filename="$(find rox_description)/urdf/xacros/franka_arm.urdf.xacro"/>
</xacro:if>

<!-- add gripper-->
<xacro:unless value="${gripper == ''}">

Expand Down
56 changes: 56 additions & 0 deletions rox_description/urdf/xacros/franka_arm.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
<?xml version="1.0"?>
<!--
Author: Pradheep Padmanabhan
Contributor: Ashin Anandakrishnan
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="franka_arm">

<xacro:include filename="$(find franka_description)/robots/common/franka_robot.xacro"/>

<xacro:arg name="use_gz" default="false"/>
<xacro:arg name="include_arm_ros2_control" default="false"/>
<xacro:arg name="arm" default="fr3"/>
<xacro:arg name="use_mock_hardware" default="false"/>
<xacro:arg name="mock_sensor_commands" default="false"/>
<xacro:arg name="simulation_controllers" default=""/>

<xacro:property name="joint_limits"
value="${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')}" />
<xacro:property name="kinematics"
value="${xacro.load_yaml('$(find franka_description)/robots/fr3/kinematics.yaml')}" />
<xacro:property name="inertials"
value="${xacro.load_yaml('$(find franka_description)/robots/fr3/inertials.yaml')}" />
<xacro:property name="dynamics"
value="${xacro.load_yaml('$(find franka_description)/robots/fr3/dynamics.yaml')}" />

<xacro:if value="${arm == 'fr3'}">
<xacro:property name="arm_height" value="0.276"/>
<xacro:arg name="arm_parent" default="world"/>
<xacro:arg name="initial_positions_file"
default="$(find rox_bringup)/configs/franka/initial_joint_positions.yaml"/>
<xacro:property name="franka_initial_positions"
value="${xacro.load_yaml('$(arg initial_positions_file)')}"/>

<xacro:franka_robot
arm_id="fr3"
hand="false"
joint_limits="${joint_limits}"
kinematics="${kinematics}"
inertials="${inertials}"
dynamics="${dynamics}"
xyz="0.218 0 ${arm_height}"
parent="cabinet_link"
gazebo="$(arg use_gz)"
ros2_control="$(arg include_arm_ros2_control)"
description_pkg="franka_description"
gazebo_effort="false"

controller_yaml="$(arg simulation_controllers)"
/>
<!-- If a controller_yaml file is provided, it gets passed down into the
franka_arm_ros2_control macro(customised). If empty, the macro falls back to the
default Franka gazebo controller config. -->

</xacro:if>

</robot>