67 lines
3.1 KiB
XML
67 lines
3.1 KiB
XML
<?xml version='1.0' encoding='utf-8'?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="fer">
|
|
|
|
<xacro:include filename="$(find franka_description)/robots/common/franka_robot.xacro"/>
|
|
|
|
<!--
|
|
DEPRECATION NOTICE
|
|
argument arm_id is no longer supported and will be removed in the future.
|
|
This argument is ignored.
|
|
-->
|
|
<xacro:arg name="arm_id" default="fer" />
|
|
|
|
<!-- Don't print a prefix for joints, visuals, and links? -->
|
|
<xacro:arg name="no_prefix" default="false"/>
|
|
|
|
<!-- Should an end-effector be mounted at the flange?" -->
|
|
<xacro:arg name="hand" default="true" />
|
|
|
|
<!-- Which end-effector would be mounted at the flange?" -->
|
|
<xacro:arg name="ee_id" default="franka_hand" />
|
|
|
|
<!-- Is the robot being simulated in gazebo?" -->
|
|
<xacro:arg name="gazebo" default="false" />
|
|
<!-- If `gazebo` arg is set, to which frame shall $(arm_id)_link0 be parented. Empty string for not fixing at all -->
|
|
<xacro:arg name="parent" default="world" />
|
|
<!-- If `gazebo` arg is set and `parent` not empty, what position offset between `parent` & $(arm_id)_link0 -->
|
|
<xacro:arg name="xyz" default="0 0 0" />
|
|
<!-- If `gazebo` arg is set and `parent` not empty, what rotation offset between `parent` & $(arm_id)_link0 -->
|
|
<xacro:arg name="rpy" default="0 0 0" />
|
|
|
|
<!-- Should self-collision be enabled? -->
|
|
<xacro:arg name="with_sc" default="false" />
|
|
|
|
<!-- Is the robot being controlled with ros2_control?" -->
|
|
<xacro:arg name="ros2_control" default="false" />
|
|
<!-- IP address or hostname of the robot" -->
|
|
<xacro:arg name="robot_ip" default="" />
|
|
<!-- Should a fake hardware be used? -->
|
|
<xacro:arg name="use_fake_hardware" default="false" />
|
|
<!-- Should fake sensors be used? -->
|
|
<xacro:arg name="fake_sensor_commands" default="false" />
|
|
<!-- Should the robot be spawned in Gazebo with effort interfaces?" -->
|
|
<xacro:arg name="gazebo_effort" default="false" />
|
|
|
|
<!-- For a multi arm setup, we need a threaded robot running async-->
|
|
<xacro:arg name="multi_arm" default="false" />
|
|
|
|
<xacro:franka_robot arm_id="fer"
|
|
joint_limits="${xacro.load_yaml('$(find franka_description)/robots/fer/joint_limits.yaml')}"
|
|
inertials="${xacro.load_yaml('$(find franka_description)/robots/fer/inertials.yaml')}"
|
|
kinematics="${xacro.load_yaml('$(find franka_description)/robots/fer/kinematics.yaml')}"
|
|
dynamics="${xacro.load_yaml('$(find franka_description)/robots/fer/dynamics.yaml')}"
|
|
gazebo="$(arg gazebo)"
|
|
hand="$(arg hand)"
|
|
ee_id="$(arg ee_id)"
|
|
with_sc="$(arg with_sc)"
|
|
ros2_control="$(arg ros2_control)"
|
|
robot_ip="$(arg robot_ip)"
|
|
use_fake_hardware="$(arg use_fake_hardware)"
|
|
fake_sensor_commands="$(arg fake_sensor_commands)"
|
|
gazebo_effort="$(arg gazebo_effort)"
|
|
no_prefix="$(arg no_prefix)"
|
|
arm_prefix= ""
|
|
connected_to= "base">
|
|
</xacro:franka_robot>
|
|
</robot>
|