initial forking commit

This commit is contained in:
2025-02-22 22:37:34 +09:00
commit ee5f8b145e
106 changed files with 13922 additions and 0 deletions

View File

@@ -0,0 +1,88 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="franka_arm_ros2_control"
params="arm_id
robot_ip
use_fake_hardware:=^|false
fake_sensor_commands:=^|false
gazebo:=^|false
hand:=^|false
gazebo_effort:=^|false
arm_prefix:=''
multi_arm:=false">
<xacro:property name="arm_prefix_modified" value="${'' if arm_prefix == '' else arm_prefix + '_'}" />
<ros2_control name="${arm_prefix_modified}FrankaHardwareInterface" type="system">
<hardware>
<param name="arm_id">${arm_id}</param>
<param name="prefix">${arm_prefix}</param>
<xacro:if value="${use_fake_hardware}">
<plugin>fake_components/GenericSystem</plugin>
<param name="fake_sensor_commands">${fake_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:if value="${gazebo}">
<plugin>franka_ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:if value="${use_fake_hardware == 0 and gazebo == 0 and multi_arm == 0}">
<plugin>franka_hardware/FrankaHardwareInterface</plugin>
<param name="robot_ip">${robot_ip}</param>
<param name="arm_prefix">${arm_prefix}</param>
</xacro:if>
<xacro:if value="${use_fake_hardware == 0 and gazebo == 0 and multi_arm == 1}">
<plugin>franka_hardware/MultiFrankaHardwareInterface</plugin>
<param name="robot_ip">${robot_ip}</param>
<param name="arm_prefix">${arm_prefix}</param>
</xacro:if>
</hardware>
<xacro:macro name="configure_joint" params="joint_name initial_position">
<joint name="${joint_name}">
<!--
deactivated for gazebo velocity and position interface due to a bug
https://github.com/ros-controls/gz_ros2_control/issues/343
Command Interfaces -->
<xacro:if value="${multi_arm == 0}">
<command_interface name="position"/>
<command_interface name="velocity"/>
</xacro:if>
<xacro:if value="${gazebo == 0 or gazebo_effort == 1}">
<command_interface name="effort"/>
</xacro:if>
<!-- State Interfaces -->
<state_interface name="position">
<param name="initial_value">${initial_position}</param>
</state_interface>
<state_interface name="velocity"/>
<param name="initial_value">0.0</param>
<state_interface name="effort"/>
</joint>
</xacro:macro>
<xacro:configure_joint joint_name="${arm_prefix_modified}${arm_id}_joint1" initial_position="0.0"/>
<xacro:configure_joint joint_name="${arm_prefix_modified}${arm_id}_joint2" initial_position="${-pi/4}"/>
<xacro:configure_joint joint_name="${arm_prefix_modified}${arm_id}_joint3" initial_position="0.0"/>
<xacro:configure_joint joint_name="${arm_prefix_modified}${arm_id}_joint4" initial_position="${-3*pi/4}"/>
<xacro:configure_joint joint_name="${arm_prefix_modified}${arm_id}_joint5" initial_position="0.0"/>
<xacro:configure_joint joint_name="${arm_prefix_modified}${arm_id}_joint6" initial_position="${pi/2}"/>
<xacro:configure_joint joint_name="${arm_prefix_modified}${arm_id}_joint7" initial_position="${pi/4}"/>
<xacro:if value="${gazebo and hand}">
<xacro:configure_joint joint_name="${arm_id}_finger_joint1" initial_position="0.0" />
</xacro:if>
</ros2_control>
<xacro:if value="${gazebo}">
<gazebo>
<plugin filename="franka_ign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<parameters>$(find franka_gazebo_bringup)/config/franka_gazebo_controllers.yaml</parameters>
</plugin>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,153 @@
<?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/utils.xacro" />
<!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
<!-- arm_id: Namespace of the robot arm. Serves to differentiate between arms in case of multiple instances. -->
<!-- joint_limits: description of the joint limits that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')} -->
<!-- kinematics: description of the kinematics that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/kinematics.yaml')} -->
<!-- inertials: description of the inertials that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/inertials.yaml')} -->
<!-- dynamics: description of the dynamics that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/dynamics.yaml')} -->
<xacro:macro name="franka_arm" params="arm_id arm_prefix:='' no_prefix:=false description_pkg:='franka_description' connected_to:='base' xyz:='0 0 0' rpy:='0 0 0' gazebo:='false' safety_distance:=0 joint_limits inertials kinematics dynamics with_sc:=false" >
<!-- Define a property that defaults to 'arm_prefix_arm_id' concatenated with an underscore if 'no_prefix' is not set -->
<xacro:property name="prefix" value="${'' if no_prefix else arm_prefix + arm_id + '_'}" />
<xacro:if value="${gazebo}">
<xacro:property name="connected_to" value="" />
</xacro:if>
<xacro:unless value="${not connected_to}">
<link name="${connected_to}">
</link>
<joint name="${prefix}${connected_to}_joint" type="fixed">
<parent link="${connected_to}"/>
<child link="${prefix}link0"/>
<origin rpy="${rpy}" xyz="${xyz}"/>
</joint>
</xacro:unless>
<xacro:link_with_sc no_prefix="${no_prefix}" name="link0" gazebo="${gazebo}" with_sc="${with_sc}">
<self_collision_geometries>
<xacro:collision_capsule xyz="-0.075 0 0.06" direction="x" radius="${0.06+safety_distance}" length="0.03" />
</self_collision_geometries>
</xacro:link_with_sc>
<xacro:link_with_sc no_prefix="${no_prefix}" name="link1" gazebo="${gazebo}" with_sc="${with_sc}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 -191.5e-3" radius="${0.06+safety_distance}" length="0.283" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${prefix}joint1" type="revolute">
<xacro:franka-kinematics name="joint1" config="${kinematics}" />
<parent link="${prefix}link0" />
<child link="${prefix}link1" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint1" config="${joint_limits}" />
<xacro:franka-dynamics name="joint1" config="${dynamics}" />
</joint>
<xacro:link_with_sc no_prefix="${no_prefix}" name="link2" gazebo="${gazebo}" with_sc="${with_sc}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 0" radius="${0.06+safety_distance}" length="0.12" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${prefix}joint2" type="revolute">
<xacro:franka-kinematics name="joint2" config="${kinematics}" />
<parent link="${prefix}link1" />
<child link="${prefix}link2" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint2" config="${joint_limits}" />
<xacro:franka-dynamics name="joint2" config="${dynamics}" />
</joint>
<xacro:link_with_sc no_prefix="${no_prefix}" name="link3" gazebo="${gazebo}" with_sc="${with_sc}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 -0.145" radius="${0.06+safety_distance}" length="0.15" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${prefix}joint3" type="revolute">
<xacro:franka-kinematics name="joint3" config="${kinematics}" />
<parent link="${prefix}link2" />
<child link="${prefix}link3" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint3" config="${joint_limits}" />
<xacro:franka-dynamics name="joint3" config="${dynamics}" />
</joint>
<xacro:link_with_sc no_prefix="${no_prefix}" name="link4" gazebo="${gazebo}" with_sc="${with_sc}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 0" radius="${0.06+safety_distance}" length="0.12" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${prefix}joint4" type="revolute">
<xacro:franka-kinematics name="joint4" config="${kinematics}" />
<parent link="${prefix}link3" />
<child link="${prefix}link4" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint4" config="${joint_limits}" />
<xacro:franka-dynamics name="joint4" config="${dynamics}" />
</joint>
<xacro:link_with_sc no_prefix="${no_prefix}" name="link5" gazebo="${gazebo}" with_sc="${with_sc}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 -0.26" radius="${0.060+safety_distance}" length="0.10" />
<xacro:collision_capsule xyz="0 0.08 -0.13" radius="${0.025+safety_distance}" length="0.14" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${prefix}joint5" type="revolute">
<xacro:franka-kinematics name="joint5" config="${kinematics}" />
<parent link="${prefix}link4" />
<child link="${prefix}link5" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint5" config="${joint_limits}" />
<xacro:franka-dynamics name="joint5" config="${dynamics}" />
</joint>
<xacro:link_with_sc no_prefix="${no_prefix}" name="link6" gazebo="${gazebo}" with_sc="${with_sc}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 -0.03" radius="${0.05+safety_distance}" length="0.08" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${prefix}joint6" type="revolute">
<xacro:franka-kinematics name="joint6" config="${kinematics}" />
<parent link="${prefix}link5" />
<child link="${prefix}link6" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint6" config="${joint_limits}" />
<xacro:franka-dynamics name="joint6" config="${dynamics}" />
</joint>
<xacro:link_with_sc no_prefix="${no_prefix}" name="link7" gazebo="${gazebo}" rpy="0 0 ${pi/4}" with_sc="${with_sc}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 0.01" direction="z" radius="${0.04+safety_distance}" length="0.14" />
<xacro:collision_capsule xyz="0.06 0 0.082" direction="x" radius="${0.03+safety_distance}" length="0.01" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${prefix}joint7" type="revolute">
<xacro:franka-kinematics name="joint7" config="${kinematics}" />
<parent link="${prefix}link6"/>
<child link="${prefix}link7"/>
<axis xyz="0 0 1"/>
<xacro:franka-limits name="joint7" config="${joint_limits}" />
<xacro:franka-dynamics name="joint7" config="${dynamics}" />
</joint>
<link name="${prefix}link8"/>
<joint name="${prefix}joint8" type="fixed">
<xacro:franka-kinematics name="joint8" config="${kinematics}" />
<parent link="${prefix}link7" />
<child link="${prefix}link8" />
</joint>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,167 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="franka_robot"
params="arm_id
joint_limits
kinematics
inertials
dynamics
parent:='world'
xyz:='0 0 0'
rpy:='0 0 0'
hand:='true'
ee_id:=none
gazebo:='false'
with_sc:='false'
ros2_control:=false
robot_ip:=''
use_fake_hardware:=false
fake_sensor_commands:=false
gazebo_effort:=false
no_prefix:='false'
arm_prefix:=''
connected_to:='base'
multi_arm:=false">
<xacro:include filename="$(find franka_description)/robots/common/utils.xacro" />
<xacro:include filename="$(find franka_description)/robots/common/franka_arm.xacro" />
<xacro:property name="arm_prefix_modified" value="${'' if arm_prefix == '' else arm_prefix + '_'}" />
<xacro:franka_arm
arm_id="${arm_id}"
arm_prefix="${arm_prefix_modified}"
no_prefix="${no_prefix}"
xyz="${xyz}"
rpy="${rpy}"
safety_distance="0.03"
gazebo="${gazebo}"
joint_limits="${joint_limits}"
kinematics="${kinematics}"
inertials="${inertials}"
dynamics="${dynamics}"
with_sc="${with_sc}"
connected_to="${connected_to}"
/>
<xacro:if value="${hand and ee_id == 'franka_hand'}">
<xacro:include filename="$(find franka_description)/end_effectors/common/franka_hand.xacro"/>
<xacro:include filename="$(find franka_description)/end_effectors/common/utils.xacro" />
<xacro:include filename="$(find franka_description)/end_effectors/$(arg ee_id)/$(arg ee_id)_arguments.xacro" />
<xacro:if value="${arm_id == 'fp3'}">
<xacro:property name="ee_color" value="black" />
</xacro:if>
<xacro:if value="${arm_id == 'fr3' or arm_id == 'fer'}">
<xacro:property name="ee_color" value="white" />
</xacro:if>
<xacro:property name="special_connection" value="$(arg special_connection)" />
<xacro:property name="connection" value="${special_connection if special_connection != '' else arm_id + '_link8'}" />
<xacro:franka_hand
connected_to="${arm_prefix_modified}${connection}"
arm_id="${arm_id}"
arm_prefix="${arm_prefix_modified}"
ee_id="${ee_id}_${ee_color}"
ee_inertials="${xacro.load_yaml('$(find franka_description)/end_effectors/$(arg ee_id)/inertials.yaml')}"
rpy_ee="$(arg rpy_ee)"
xyz_ee="$(arg xyz_ee)"
tcp_xyz="$(arg tcp_xyz)"
tcp_rpy="$(arg tcp_rpy)"
safety_distance="$(arg safety_distance)"
gazebo="${gazebo}"
description_pkg="$(arg description_pkg)"
with_sc="${with_sc}"
/>
</xacro:if>
<xacro:if value="${hand and ee_id != 'none' and ee_id != 'franka_hand'}">
<xacro:include filename="$(find franka_description)/end_effectors/common/ee_with_one_link.xacro"/>
<xacro:include filename="$(find franka_description)/end_effectors/common/utils.xacro" />
<xacro:include filename="$(find franka_description)/end_effectors/$(arg ee_id)/$(arg ee_id)_arguments.xacro" />
<xacro:property name="special_connection" value="$(arg special_connection)" />
<xacro:property name="connection" value="${special_connection if special_connection == '' else arm_id + '_link8'}" />
<xacro:ee_with_one_link
connected_to="${arm_prefix_modified}${connection}"
arm_id="${arm_id}"
arm_prefix="${arm_prefix_modified}"
ee_id="${ee_id}"
ee_inertials="${xacro.load_yaml('$(find franka_description)/end_effectors/$(arg ee_id)/inertials.yaml')}"
rpy_ee="$(arg rpy_ee)"
xyz_ee="$(arg xyz_ee)"
tcp_xyz="$(arg tcp_xyz)"
tcp_rpy="$(arg tcp_rpy)"
safety_distance="$(arg safety_distance)"
gazebo="${gazebo}"
description_pkg="$(arg description_pkg)"
with_sc="${with_sc}"
/>
</xacro:if>
<!-- Definition of additional Gazebo tags -->
<xacro:if value="${gazebo}">
<xacro:if value="${parent != ''}">
<!-- Gazebo requires a joint to a link called "world" for statically mounted robots -->
<xacro:if value="${parent == 'world'}">
<link name="${parent}" />
</xacro:if>
<joint name="${parent}_joint" type="fixed">
<origin xyz="${xyz}" rpy="${rpy}" />
<parent link="${parent}" />
<child link="${arm_id}_link0" />
</joint>
</xacro:if>
<xacro:gazebo-joint joint="${arm_id}_joint1" transmission="hardware_interface/PositionJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint2" transmission="hardware_interface/PositionJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint3" transmission="hardware_interface/PositionJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint4" transmission="hardware_interface/PositionJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint5" transmission="hardware_interface/PositionJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint6" transmission="hardware_interface/PositionJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint7" transmission="hardware_interface/PositionJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint1" transmission="hardware_interface/VelocityJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint2" transmission="hardware_interface/VelocityJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint3" transmission="hardware_interface/VelocityJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint4" transmission="hardware_interface/VelocityJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint5" transmission="hardware_interface/VelocityJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint6" transmission="hardware_interface/VelocityJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint7" transmission="hardware_interface/VelocityJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint1" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint2" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint3" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint4" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint5" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint6" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_joint7" transmission="hardware_interface/EffortJointInterface" />
<xacro:transmission-franka-state arm_id="${arm_id}" />
<xacro:transmission-franka-model arm_id="${arm_id}"
root="${arm_id}_joint1"
tip="${arm_id}_joint8"
/>
<xacro:if value="${ee_id == 'franka_hand'}">
<xacro:gazebo-joint joint="${arm_id}_finger_joint1" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_finger_joint2" transmission="hardware_interface/EffortJointInterface" />
<!-- Friction specific material for Rubber/Rubber contact -->
<xacro:gazebo-friction link="${arm_id}_leftfinger" mu="1.13" />
<xacro:gazebo-friction link="${arm_id}_rightfinger" mu="1.13" />
</xacro:if>
</xacro:if>
<xacro:if value="${ros2_control}">
<xacro:include filename="$(find franka_description)/robots/common/franka_arm.ros2_control.xacro"/>
<xacro:franka_arm_ros2_control
arm_id="${arm_id}"
robot_ip="${robot_ip}"
use_fake_hardware="$(arg use_fake_hardware)"
fake_sensor_commands="$(arg fake_sensor_commands)"
gazebo="$(arg gazebo)"
hand="$(arg hand)"
gazebo_effort="$(arg gazebo_effort)"
arm_prefix="${arm_prefix}"
multi_arm="$(arg multi_arm)"
/>
</xacro:if>
</xacro:macro>
</robot>

269
robots/common/utils.xacro Normal file
View File

@@ -0,0 +1,269 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- ============================================================== -->
<!-- Macro to add an <inertial> tag based on yaml-load properties -->
<!-- -->
<!-- name: Name of the robot link (without prefix) -->
<!-- inertial: Dictionary of inertia properties (see inertial.yaml) -->
<!-- ============================================================== -->
<xacro:macro name="franka-inertials" params="name inertials:=^">
<xacro:unless value="${name in inertials}">${xacro.warning('No inertia properties defined for: ' + name)}</xacro:unless>
<xacro:if value="${name in inertials}">
<!-- Access inertia properties of link 'name' -->
<xacro:property name="link_inertials" value="${inertials[name]}" lazy_eval="false" />
<inertial>
<origin rpy="${link_inertials.origin.rpy}" xyz="${link_inertials.origin.xyz}" />
<mass value="${link_inertials.mass}" />
<xacro:if value="${'inertia' in link_inertials}">
<xacro:property name="I" value="${link_inertials.inertia}" />
<inertia ixx="${I.xx}" ixy="${I.xy}" ixz="${I.xz}" iyy="${I.yy}" iyz="${I.yz}" izz="${I.zz}" />
</xacro:if>
</inertial>
</xacro:if>
</xacro:macro>
<!-- ========================================================== -->
<!-- Macro to add a single link, both with -->
<!-- * detailed meshes for environmental collision checking -->
<!-- * and coarse geometry models for self-collision checking -->
<!-- (only if 'gazebo' param is set) -->
<!-- -->
<!-- name: Name of the robot link (without prefix) -->
<!-- rpy: Rotation of the *_sc link relative to parent [rad] -->
<!-- self_collision_geometries: self <collision> models -->
<!-- ========================================================== -->
<xacro:macro name="link_with_sc" params="name no_prefix:='false' rpy:='0 0 0' **self_collision_geometries gazebo:=false with_sc:=false">
<xacro:property name="prefix" value="${'' if no_prefix else arm_prefix + arm_id + '_'}" />
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="${prefix}${name}">
<visual name="${prefix}${name}_visual">
<geometry>
<mesh filename="package://${description_pkg}/meshes/robot_arms/${arm_id}/visual/${name}.dae" />
</geometry>
</visual>
<collision name="${prefix}${name}_collision">
<geometry>
<mesh filename="package://franka_description/meshes/robot_arms/${arm_id}/collision/${name}.stl" />
</geometry>
</collision>
<xacro:franka-inertials name="${name}" />
</link>
<!-- sub-link defining coarse geometries of real robot's internal self-collision -->
<xacro:if value="${with_sc}">
<link name="${prefix}${name}_sc">
<xacro:unless value="${gazebo}">
<xacro:insert_block name="self_collision_geometries" />
</xacro:unless>
</link>
<!-- fixed joint between both sub-links -->
<joint name="${prefix}${name}_sc_joint" type="fixed">
<origin rpy="${rpy}" />
<parent link="${prefix}${name}" />
<child link="${prefix}${name}_sc" />
</joint>
</xacro:if>
</xacro:macro>
<!-- =========================================================== -->
<!-- Add a <collision> tag with a capsule, made from a cylinder -->
<!-- with two spheres at its caps. The capsule will always be -->
<!-- aligned with the axis of 'direction' you pass along. -->
<!-- -->
<!-- radius: Radii of both the cylinder and both spheres [m] -->
<!-- length: Length of the cylinder/distance between the centers -->
<!-- of the spheres. NOT overall length of capsule! -->
<!-- xyz: Position of the center of the capsule/cylinder -->
<!-- direction: One of { x, y, z, -x, -y, -z } -->
<!-- =========================================================== -->
<xacro:macro name="collision_capsule" params="radius length xyz:='0 0 0' direction:='z'">
<xacro:property name="r" value="${pi/2.0 if 'y' in direction else 0}" />
<xacro:property name="p" value="${pi/2.0 if 'x' in direction else 0}" />
<xacro:property name="y" value="0" />
<xacro:property name="x" value="${xyz.split(' ')[0]}" />
<xacro:property name="y" value="${xyz.split(' ')[1]}" />
<xacro:property name="z" value="${xyz.split(' ')[2]}" />
<!-- Sphere center offsets from center of cylinder -->
<xacro:property name="sx" value="${length / 2.0 if 'x' in direction else 0}" />
<xacro:property name="sy" value="${length / 2.0 if 'y' in direction else 0}" />
<xacro:property name="sz" value="${length / 2.0 if 'z' in direction else 0}" />
<collision>
<origin xyz="${x} ${y} ${z}" rpy="${r} ${p} ${y}"/>
<geometry>
<cylinder radius="${radius}" length="${length}" />
</geometry>
</collision>
<collision>
<origin xyz="${x+sx} ${y+sy} ${z+sz}" />
<geometry>
<sphere radius="${radius}" />
</geometry>
</collision>
<collision>
<origin xyz="${x-sx} ${y-sy} ${z-sz}" />
<geometry>
<sphere radius="${radius}" />
</geometry>
</collision>
</xacro:macro>
<!-- ========================================================== -->
<!-- Adds the required tags to simulate one joint in gazebo -->
<!-- -->
<!-- joint - Name of the fer joint to simulate -->
<!-- transmission - type of the transmission of the joint -->
<!-- ========================================================== -->
<xacro:macro name="gazebo-joint" params="joint transmission:=hardware_interface/EffortJointInterface">
<gazebo reference="${joint}">
<!-- Needed for ODE to output external wrenches on joints -->
<provideFeedback>true</provideFeedback>
</gazebo>
<transmission name="${joint}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint}">
<hardwareInterface>${transmission}</hardwareInterface>
</joint>
<actuator name="${joint}_motor">
<hardwareInterface>${transmission}</hardwareInterface>
</actuator>
</transmission>
</xacro:macro>
<xacro:macro name="gazebo-friction" params="link mu">
<gazebo reference="${link}">
<collision>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode>
<!-- These two parameter need application specific tuning. -->
<!-- Usually you want no "snap out" velocity and a generous -->
<!-- penetration depth to keep the grasping stable -->
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<ode>
<mu>${mu}</mu>
<mu2>${mu}</mu2>
</ode>
</friction>
<bounce/>
</surface>
</collision>
</gazebo>
</xacro:macro>
<!-- ========================================================== -->
<!-- Adds the required tags to provide a `FrankaStateInterface` -->
<!-- when simulating with franka_hw_sim plugin -->
<!-- -->
<!-- arm_id - Arm ID of the fer to simulate (default 'fer') -->
<!-- ========================================================== -->
<xacro:macro name="transmission-franka-state" params="arm_id:=fer">
<transmission name="${arm_prefix}${arm_id}_franka_state">
<type>franka_hw/FrankaStateInterface</type>
<joint name="${arm_prefix}${arm_id}_joint1"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_prefix}${arm_id}_joint2"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_prefix}${arm_id}_joint3"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_prefix}${arm_id}_joint4"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_prefix}${arm_id}_joint5"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_prefix}${arm_id}_joint6"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_prefix}${arm_id}_joint7"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<actuator name="${arm_prefix}${arm_id}_motor1"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_prefix}${arm_id}_motor2"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_prefix}${arm_id}_motor3"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_prefix}${arm_id}_motor4"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_prefix}${arm_id}_motor5"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_prefix}${arm_id}_motor6"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_prefix}${arm_id}_motor7"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
</transmission>
</xacro:macro>
<!-- ============================================================ -->
<!-- Adds the required tags to provide a `FrankaModelInterface` -->
<!-- when simulating with franka_hw_sim plugin -->
<!-- -->
<!-- arm_id - Arm ID of the fer to simulate (default 'fer') -->
<!-- root - Joint name of the base of the robot -->
<!-- tip - Joint name of the tip of the robot (flange or hand) -->
<!-- ============================================================ -->
<xacro:macro name="transmission-franka-model" params="arm_id:=fer root:=fer_joint1 tip:=fer_joint7">
<transmission name="${arm_prefix}${arm_id}_franka_model">
<type>franka_hw/FrankaModelInterface</type>
<joint name="${root}">
<role>root</role>
<hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface>
</joint>
<joint name="${tip}">
<role>tip</role>
<hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface>
</joint>
<actuator name="${root}_motor_root"><hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface></actuator>
<actuator name="${tip}_motor_tip" ><hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface></actuator>
</transmission>
</xacro:macro>
<xacro:macro name="inertia-cylinder" params="mass radius h">
<inertial>
<mass value="${mass}" />
<inertia ixx="${1./12 * mass * (3 * radius**2 + h**2)}" ixy = "0" ixz = "0"
iyy="${1./12 * mass * (3 * radius**2 + h**2)}" iyz = "0"
izz="${1./2 * mass * radius**2}" />
</inertial>
</xacro:macro>
<!-- ========================================================================= -->
<!-- Adds the <limit ... /> & <safety_controller/> tags given a config file -->
<!-- of joint limits -->
<!-- -->
<!-- config - YAML struct defining joint limits (e.g. fer/joint_limits.yaml) -->
<!-- name - Name of the joint for which to add limits to -->
<!-- ========================================================================= -->
<xacro:macro name="franka-limits" params="config name">
<xacro:property name="limits" value="${config[name]['limit']}" lazy_eval="false" />
<limit lower="${limits.lower}"
upper="${limits.upper}"
effort="${limits.effort}"
velocity="${limits.velocity}" />
<safety_controller k_position="100.0"
k_velocity="40.0"
soft_lower_limit="${limits.lower}"
soft_upper_limit="${limits.upper}" />
</xacro:macro>
<!-- ========================================================================= -->
<!-- Adds the <dynamics ... /> tag given a config file of joint dynamics -->
<!-- -->
<!-- config - YAML struct defining joint dynamics (e.g. fer/dynamics.yaml) -->
<!-- name - Name of the joint for which to add dynamics to -->
<!-- ========================================================================= -->
<xacro:macro name="franka-dynamics" params="config name">
<xacro:property name="dynamics" value="${config[name]['dynamic']}" lazy_eval="false" />
<dynamics D="${dynamics.D}"
K="${dynamics.K}"
damping="${dynamics.damping}"
friction="${dynamics.friction}"
mu_coulomb="${dynamics.mu_coulomb}"
mu_viscous="${dynamics.mu_viscous}" />
</xacro:macro>
<!-- ========================================================================= -->
<!-- Adds the <kinematics ... /> tag given a config file of joint kinematics -->
<!-- -->
<!-- config - YAML struct defining joint kinematics (e.g. fer/kinematics.yaml) -->
<!-- name - Name of the joint for which to add kinematics to -->
<!-- ========================================================================= -->
<xacro:macro name="franka-kinematics" params="config name">
<xacro:property name="kinematics" value="${config[name]['kinematic']}" lazy_eval="false" />
<origin rpy="${kinematics.roll} ${kinematics.pitch} ${kinematics.yaw}"
xyz="${kinematics.x} ${kinematics.y} ${kinematics.z}" />
</xacro:macro>
</robot>

62
robots/fer/dynamics.yaml Normal file
View File

@@ -0,0 +1,62 @@
joint1:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint2:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint3:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint4:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint5:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint6:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint7:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16

66
robots/fer/fer.urdf.xacro Normal file
View File

@@ -0,0 +1,66 @@
<?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>

96
robots/fer/inertials.yaml Normal file
View File

@@ -0,0 +1,96 @@
link0:
origin:
xyz: -0.0172 0.0004 0.0745
rpy: 0 0 0
mass: 2.3966
inertia:
xx: 0.0090
xy: 0.0000
xz: 0.0020
yy: 0.0115
yz: 0.0000
zz: 0.0085
link1:
origin:
xyz: 0.00033 -0.02204 -0.04762
rpy: 0 0 0
mass: 2.7907
inertia:
xx: 0.01564782655
xy: 0.00000531236
xz: -0.00003676721
yy: 0.01439883526
yz: -0.00248480843
zz: 0.00500443991
link2:
origin:
xyz: 0.00038 -0.09211 0.01908
rpy: 0 0 0
mass: 2.5420
inertia:
xx: 0.01662427728
xy: 0.00003086077
xz: 0.00000835940
yy: 0.00462501261
yz: 0.00355899830
zz: 0.01545124526
link3:
origin:
xyz: 0.05152 0.01696 -0.02971
rpy: 0 0 0
mass: 2.2513
inertia:
xx: 0.00631741992
xy: 0.00097309955
xz: 0.00292525834
yy: 0.00866285493
yz: 0.00093469224
zz: 0.00657804051
link4:
origin:
xyz: -0.05113 0.05825 0.01698
rpy: 0 0 0
mass: 2.2037
inertia:
xx: 0.00784585566
xy: -0.00339591957
xz: 0.00158704074
yy: 0.00649543136
yz: -0.00181477884
zz: 0.01003079917
link5:
origin:
xyz: -0.00005 0.03730 -0.09280
rpy: 0 0 0
mass: 2.2855
inertia:
xx: 0.02297014781
xy: -0.00000949345
xz: -0.00002063156
yy: 0.02095060919
yz: 0.00382345782
zz: 0.00430606551
link6:
origin:
xyz: 0.06572 -0.00371 0.00153
rpy: 0 0 0
mass: 1.353
inertia:
xx: 0.00087964522
xy: -0.00021487814
xz: -0.00011911662
yy: 0.00277796968
yz: 0.00001274322
zz: 0.00286701969
link7:
origin:
xyz: 0.00089 -0.00044 0.05491
rpy: 0 0 0
mass: 0.35973
inertia:
xx: 0.00019541063
xy: 0.00000165231
xz: 0.00000148826
yy: 0.00019210361
yz: -0.00000131132
zz: 0.00017936256

View File

@@ -0,0 +1,48 @@
joint1:
limit:
lower: -2.8973
upper: 2.8973
velocity: 2.1750
effort: 87.0
joint2:
limit:
lower: -1.7628
upper: 1.7628
velocity: 2.1750
effort: 87.0
joint3:
limit:
lower: -2.8973
upper: 2.8973
velocity: 2.1750
effort: 87.0
joint4:
limit:
lower: -3.0718
upper: -0.0698
velocity: 2.1750
effort: 87.0
joint5:
limit:
lower: -2.8973
upper: 2.8973
velocity: 2.6100
effort: 12.0
joint6:
limit:
lower: -0.0175
upper: 3.7525
velocity: 2.6100
effort: 12.0
joint7:
limit:
lower: -2.8973
upper: 2.8973
velocity: 2.6100
effort: 12.0

View File

@@ -0,0 +1,72 @@
joint1:
kinematic:
x: 0
y: 0
z: 0.333
roll: 0
pitch: 0
yaw: 0
joint2:
kinematic:
x: 0
y: 0
z: 0
roll: -1.570796326794897
pitch: 0
yaw: 0
joint3:
kinematic:
x: 0
y: -0.316
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint4:
kinematic:
x: 0.0825
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint5:
kinematic:
x: -0.0825
y: 0.384
z: 0
roll: -1.570796326794897
pitch: 0
yaw: 0
joint6:
kinematic:
x: 0
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint7:
kinematic:
x: 0.088
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
# Joint to tool origin
joint8:
kinematic:
x: 0
y: 0
z: 0.107
roll: 0
pitch: 0
yaw: 0

62
robots/fp3/dynamics.yaml Normal file
View File

@@ -0,0 +1,62 @@
joint1:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint2:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint3:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint4:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint5:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint6:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint7:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16

65
robots/fp3/fp3.urdf.xacro Normal file
View File

@@ -0,0 +1,65 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="fp3">
<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="fp3" />
<!-- 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" />
<!-- 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?" -->
<xacro:arg name="gazebo" 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="fp3"
joint_limits="${xacro.load_yaml('$(find franka_description)/robots/fp3/joint_limits.yaml')}"
inertials="${xacro.load_yaml('$(find franka_description)/robots/fp3/inertials.yaml')}"
kinematics="${xacro.load_yaml('$(find franka_description)/robots/fp3/kinematics.yaml')}"
dynamics="${xacro.load_yaml('$(find franka_description)/robots/fp3/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>

97
robots/fp3/inertials.yaml Normal file
View File

@@ -0,0 +1,97 @@
link0:
origin:
xyz: -0.0172 0.0004 0.0745
rpy: 0 0 0
mass: 2.3966
inertia:
xx: 0.0090
xy: 0.0000
xz: 0.0020
yy: 0.0115
yz: 0.0000
zz: 0.0085
link1:
origin:
xyz: 0.0000004128 -0.0181251324 -0.0386035970
rpy: 0 0 0
mass: 2.9274653454
inertia:
inertia:
xx: 0.023927316485107913
xy: 1.3317903455714081e-05
xz: -0.00011404774918616684
yy: 0.0224821613275756
yz: -0.0019950320628240115
zz: 0.006350098258530016
link2:
origin:
xyz: 0.0031828864 -0.0743221644 0.0088146084
rpy: 0 0 0
mass: 2.9355370338
inertia:
xx: 0.041938946257609425
xy: 0.00020257331521090626
xz: 0.004077784227179924
yy: 0.02514514885014724
yz: -0.0042252158006570156
zz: 0.06170214472888839
link3:
origin:
xyz: 0.0407015686 -0.0048200565 -0.0289730823
rpy: 0 0 0
mass: 2.2449013699
inertia:
xx: 0.02410142547240885
xy: 0.002404694559042109
xz: -0.002856269270114313
yy: 0.01974053266708178
yz: -0.002104212683891874
zz: 0.019044494482244823
link4:
origin:
xyz: -0.0459100965 0.0630492960 -0.0085187868
rpy: 0 0 0
mass: 2.6155955791
inertia:
xx: 0.03452998321913202
xy: 0.01322552265982813
xz: 0.01015142998484113
yy: 0.028881621933049058
yz: -0.0009762833870704552
zz: 0.04125471171146641
link5:
origin:
xyz: -0.0016039605 0.0292536262 -0.0972965990
rpy: 0 0 0
mass: 2.3271207594
inertia:
xx: 0.051610278463662895
xy: -0.005715173387783472
xz: -0.0035673167625872135
yy: 0.04787729713371481
yz: 0.010673985108535986
zz: 0.016423625579357254
link6:
origin:
xyz: 0.0597131221 -0.0410294666 -0.0101692726
rpy: 0 0 0
mass: 1.8170376524
inertia:
xx: 0.005412333594383447
xy: 0.006193456360285834
xz: 0.0014219289306117652
yy: 0.014058329545509979
yz: -0.0013140753741120031
zz: 0.016080817924212554
link7:
origin:
xyz: 0.0045225817 0.0086261921 -0.0161633251
rpy: 0 0 0
mass: 0.6271432862
inertia:
xx: 0.00021092389150104718
xy: -2.433299114461931e-05
xz: 4.564480393778983e-05
yy: 0.00017718568002411474
yz: 8.744070223226438e-05
zz: 5.993190599659971e-05

View File

@@ -0,0 +1,48 @@
joint1:
limit:
lower: -2.7437
upper: 2.7437
velocity: 2.62
effort: 87.0
joint2:
limit:
lower: -1.7837
upper: 1.7837
velocity: 2.62
effort: 87.0
joint3:
limit:
lower: -2.9007
upper: 2.9007
velocity: 2.62
effort: 87.0
joint4:
limit:
lower: -3.0421
upper: -0.1518
velocity: 2.62
effort: 87.0
joint5:
limit:
lower: -2.8065
upper: 2.8065
velocity: 5.26
effort: 12.0
joint6:
limit:
lower: 0.5445
upper: 4.5169
velocity: 4.18
effort: 12.0
joint7:
limit:
lower: -3.0159
upper: 3.0159
velocity: 5.26
effort: 12.0

View File

@@ -0,0 +1,72 @@
joint1:
kinematic:
x: 0
y: 0
z: 0.333
roll: 0
pitch: 0
yaw: 0
joint2:
kinematic:
x: 0
y: 0
z: 0
roll: -1.570796326794897
pitch: 0
yaw: 0
joint3:
kinematic:
x: 0
y: -0.316
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint4:
kinematic:
x: 0.0825
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint5:
kinematic:
x: -0.0825
y: 0.384
z: 0
roll: -1.570796326794897
pitch: 0
yaw: 0
joint6:
kinematic:
x: 0
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint7:
kinematic:
x: 0.088
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
# Joint to tool origin
joint8:
kinematic:
x: 0
y: 0
z: 0.107
roll: 0
pitch: 0
yaw: 0

62
robots/fr3/dynamics.yaml Normal file
View File

@@ -0,0 +1,62 @@
joint1:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint2:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint3:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint4:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint5:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint6:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16
joint7:
dynamic:
D: 1
K: 7000
damping: 0.003
friction: 0.2
mu_coulomb: 0
mu_viscous: 16

65
robots/fr3/fr3.urdf.xacro Normal file
View File

@@ -0,0 +1,65 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="fr3">
<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="fr3" />
<!-- 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" />
<!-- 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?" -->
<xacro:arg name="gazebo" 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="fr3"
joint_limits="${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')}"
inertials="${xacro.load_yaml('$(find franka_description)/robots/fr3/inertials.yaml')}"
kinematics="${xacro.load_yaml('$(find franka_description)/robots/fr3/kinematics.yaml')}"
dynamics="${xacro.load_yaml('$(find franka_description)/robots/fr3/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>

97
robots/fr3/inertials.yaml Normal file
View File

@@ -0,0 +1,97 @@
link0:
origin:
xyz: -0.0172 0.0004 0.0745
rpy: 0 0 0
mass: 2.3966
inertia:
xx: 0.0090
xy: 0.0000
xz: 0.0020
yy: 0.0115
yz: 0.0000
zz: 0.0085
link1:
origin:
xyz: 0.0000004128 -0.0181251324 -0.0386035970
rpy: 0 0 0
mass: 2.9274653454
inertia:
inertia:
xx: 0.023927316485107913
xy: 1.3317903455714081e-05
xz: -0.00011404774918616684
yy: 0.0224821613275756
yz: -0.0019950320628240115
zz: 0.006350098258530016
link2:
origin:
xyz: 0.0031828864 -0.0743221644 0.0088146084
rpy: 0 0 0
mass: 2.9355370338
inertia:
xx: 0.041938946257609425
xy: 0.00020257331521090626
xz: 0.004077784227179924
yy: 0.02514514885014724
yz: -0.0042252158006570156
zz: 0.06170214472888839
link3:
origin:
xyz: 0.0407015686 -0.0048200565 -0.0289730823
rpy: 0 0 0
mass: 2.2449013699
inertia:
xx: 0.02410142547240885
xy: 0.002404694559042109
xz: -0.002856269270114313
yy: 0.01974053266708178
yz: -0.002104212683891874
zz: 0.019044494482244823
link4:
origin:
xyz: -0.0459100965 0.0630492960 -0.0085187868
rpy: 0 0 0
mass: 2.6155955791
inertia:
xx: 0.03452998321913202
xy: 0.01322552265982813
xz: 0.01015142998484113
yy: 0.028881621933049058
yz: -0.0009762833870704552
zz: 0.04125471171146641
link5:
origin:
xyz: -0.0016039605 0.0292536262 -0.0972965990
rpy: 0 0 0
mass: 2.3271207594
inertia:
xx: 0.051610278463662895
xy: -0.005715173387783472
xz: -0.0035673167625872135
yy: 0.04787729713371481
yz: 0.010673985108535986
zz: 0.016423625579357254
link6:
origin:
xyz: 0.0597131221 -0.0410294666 -0.0101692726
rpy: 0 0 0
mass: 1.8170376524
inertia:
xx: 0.005412333594383447
xy: 0.006193456360285834
xz: 0.0014219289306117652
yy: 0.014058329545509979
yz: -0.0013140753741120031
zz: 0.016080817924212554
link7:
origin:
xyz: 0.0045225817 0.0086261921 -0.0161633251
rpy: 0 0 0
mass: 0.6271432862
inertia:
xx: 0.00021092389150104718
xy: -2.433299114461931e-05
xz: 4.564480393778983e-05
yy: 0.00017718568002411474
yz: 8.744070223226438e-05
zz: 5.993190599659971e-05

View File

@@ -0,0 +1,48 @@
joint1:
limit:
lower: -2.7437
upper: 2.7437
velocity: 2.62
effort: 87.0
joint2:
limit:
lower: -1.7837
upper: 1.7837
velocity: 2.62
effort: 87.0
joint3:
limit:
lower: -2.9007
upper: 2.9007
velocity: 2.62
effort: 87.0
joint4:
limit:
lower: -3.0421
upper: -0.1518
velocity: 2.62
effort: 87.0
joint5:
limit:
lower: -2.8065
upper: 2.8065
velocity: 5.26
effort: 12.0
joint6:
limit:
lower: 0.5445
upper: 4.5169
velocity: 4.18
effort: 12.0
joint7:
limit:
lower: -3.0159
upper: 3.0159
velocity: 5.26
effort: 12.0

View File

@@ -0,0 +1,72 @@
joint1:
kinematic:
x: 0
y: 0
z: 0.333
roll: 0
pitch: 0
yaw: 0
joint2:
kinematic:
x: 0
y: 0
z: 0
roll: -1.570796326794897
pitch: 0
yaw: 0
joint3:
kinematic:
x: 0
y: -0.316
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint4:
kinematic:
x: 0.0825
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint5:
kinematic:
x: -0.0825
y: 0.384
z: 0
roll: -1.570796326794897
pitch: 0
yaw: 0
joint6:
kinematic:
x: 0
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
joint7:
kinematic:
x: 0.088
y: 0
z: 0
roll: 1.570796326794897
pitch: 0
yaw: 0
# Joint to tool origin
joint8:
kinematic:
x: 0
y: 0
z: 0.107
roll: 0
pitch: 0
yaw: 0

View File

@@ -0,0 +1,102 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="multi_arm">
<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.
-->
<!-- Define arguments -->
<xacro:arg name="arm_ids" default="['fr3','fr3']" />
<xacro:property name="arm_ids_list" value="${$(arg arm_ids)}" />
<xacro:arg name="number_of_robots" default = "2"/>
<!-- Define arguments -->
<xacro:arg name="xyz_values" default="['0 0.1 0','0 -0.1 0']" />
<xacro:property name="xyz_list" value="${$(arg xyz_values)}" />
<!-- Define arguments -->
<xacro:arg name="rpy_values" default="['-0.7 0 0','0.7 0 0']" />
<xacro:property name="rpy_list" value="${$(arg rpy_values)}" />
<!-- 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" />
<!-- 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_ips" default="['172.16.0.2','172.16.0.3']" />
<xacro:property name="robot_ips_list" value="${$(arg robot_ips)}" />
<!-- 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?" -->
<xacro:arg name="gazebo" default="false" />
<!-- Should the robot be spawned in Gazebo with effort interfaces?" -->
<xacro:arg name="gazebo_effort" default="false" />
<!-- Prefixes for arm -->
<!-- TODO: check if the list size is correct -->
<xacro:arg name="arm_prefixes" default="['left','right']" />
<xacro:property name="arm_prefixes_list" value="${$(arg arm_prefixes)}" />
<!-- For a multi arm setup, we need a threaded robot running async-->
<xacro:arg name="multi_arm" default="true" />
<link name="base">
</link>
<!-- The multi robot setup configures 'multi_arm' by default to true s.t. it uses the async threading approach for the hardware interface -->
<xacro:macro name="loop" params="i">
<xacro:unless value="${i == $(arg number_of_robots)}">
<joint name="${arm_prefixes_list[i]}_base_joint" type="fixed">
<parent link="base"/>
<child link="${arm_prefixes_list[i]}_base"/>
<origin rpy="${rpy_list[i]}" xyz="${xyz_list[i]}"/>
</joint>
<xacro:property name="arm_id_i" value="${arm_ids_list[i]}"/>
<xacro:arg name="inertials_path" default="$(find franka_description)/robots/${arm_id_i}/inertials.yaml"/>
<xacro:arg name="kinematics_path" default="$(find franka_description)/robots/${arm_id_i}/kinematics.yaml"/>
<xacro:arg name="dynamics_path" default="$(find franka_description)/robots/${arm_id_i}/dynamics.yaml"/>
<xacro:arg name="joint_limits_path" default="$(find franka_description)/robots/${arm_id_i}/joint_limits.yaml"/>
<xacro:franka_robot arm_id="${arm_id_i}"
joint_limits="${xacro.load_yaml('$(arg joint_limits_path)')}"
inertials="${xacro.load_yaml('$(arg inertials_path)')}"
kinematics="${xacro.load_yaml('$(arg kinematics_path)')}"
dynamics="${xacro.load_yaml('$(arg dynamics_path)')}"
gazebo="$(arg gazebo)"
hand="$(arg hand)"
ee_id="$(arg ee_id)"
with_sc="$(arg with_sc)"
ros2_control="$(arg ros2_control)"
robot_ip="${robot_ips_list[i]}"
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= "${arm_prefixes_list[i]}"
connected_to="${arm_prefixes_list[i]}_base"
multi_arm="$(arg multi_arm)">
</xacro:franka_robot>
<xacro:loop i="${i+1}"/>
</xacro:unless>
</xacro:macro>
<xacro:loop i="0"/>
</robot>