Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Cosmetic changes to xacro and launch files #183

Merged
merged 5 commits into from
Nov 8, 2021
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
49 changes: 25 additions & 24 deletions franka_description/robots/panda_arm.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,20 +1,21 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">

<xacro:arg name="arm_id" default="panda" /> <!-- Name of this panda -->
<xacro:arg name="hand" default="false" /> <!-- Should a franka_gripper be mounted at the flange?" -->
<xacro:arg name="gazebo" default="false" /> <!-- Is the robot being simulated in gazebo?" -->

<xacro:property name="arm_id" value="$(arg arm_id)" />
<!-- Name of this panda -->
<xacro:arg name="arm_id" default="panda" />
<!-- Should a franka_gripper be mounted at the flange?" -->
<xacro:arg name="hand" default="false" />
<!-- Is the robot being simulated in gazebo?" -->
<xacro:arg name="gazebo" default="false" />

<xacro:unless value="$(arg gazebo)">
<!-- Create a URDF for a real hardware -->
<xacro:include filename="$(find franka_description)/robots/panda_arm.xacro" />
<xacro:panda_arm arm_id="${arm_id}" safety_distance="0.03"/>
<xacro:panda_arm arm_id="$(arg arm_id)" safety_distance="0.03"/>

<xacro:if value="$(arg hand)">
<xacro:include filename="$(find franka_description)/robots/hand.xacro"/>
<xacro:hand ns="${arm_id}" rpy="0 0 ${-pi/4}" connected_to="${arm_id}_link8" safety_distance="0.03"/>
<xacro:hand ns="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" safety_distance="0.03"/>
</xacro:if>
</xacro:unless>

Expand All @@ -27,40 +28,40 @@
<xacro:include filename="$(find franka_description)/robots/utils.xacro" />
<xacro:include filename="$(find franka_description)/robots/panda_gazebo.xacro" />

<xacro:panda_arm arm_id="${arm_id}" />
<xacro:panda_arm arm_id="$(arg arm_id)" />

<xacro:if value="$(arg hand)">
<xacro:hand ns="${arm_id}" rpy="0 0 ${-pi/4}" connected_to="${arm_id}_link8" />
<xacro:gazebo-joint joint="${arm_id}_finger_joint1" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="${arm_id}_finger_joint2" transmission="hardware_interface/EffortJointInterface" />
<xacro:hand ns="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" />
<xacro:gazebo-joint joint="$(arg arm_id)_finger_joint1" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_finger_joint2" transmission="hardware_interface/EffortJointInterface" />
</xacro:if>

<!-- Gazebo requires a joint to a link called "world" for statically mounted robots -->
<link name="world" />
<joint name="world_joint" type="fixed">
<origin xyz="$(arg xyz)" rpy="$(arg rpy)" />
<parent link="world" />
<child link="${arm_id}_link0" />
<child link="$(arg arm_id)_link0" />
</joint>


<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:gazebo-joint joint="$(arg arm_id)_joint1" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint2" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint3" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint4" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint5" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_joint6" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg 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:transmission-franka-state arm_id="$(arg arm_id)" />
<xacro:transmission-franka-model arm_id="$(arg arm_id)"
root="$(arg arm_id)_joint1"
tip="$(arg arm_id)_joint8"
/>

<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>${arm_id}</robotNamespace>
<robotNamespace>$(arg arm_id)</robotNamespace>
<controlPeriod>0.001</controlPeriod>
<robotSimType>franka_gazebo/FrankaHWSim</robotSimType>
</plugin>
Expand Down
2 changes: 1 addition & 1 deletion franka_description/robots/panda_gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<!-- || PandaRobot With Retrieval of Feasible Parameters Using || -->
<!-- || Penalty-Based Optimization || -->
<!-- || by: Claudio Gaz, Marco Cognetti, Alexander Oliva, || -->
<!-- || Paolo Robuffo Giordano, Alessandro de Lucaa || -->
<!-- || Paolo Robuffo Giordano, Alessandro de Luca || -->
<!-- =============================================================== -->

<xacro:macro name="panda_arm" params="arm_id:='panda'">
Expand Down
20 changes: 5 additions & 15 deletions franka_gazebo/launch/panda.launch
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@

<include file="$(find gazebo_ros)/launch/empty_world.launch" if="$(arg gazebo)">
<arg name="world_name" value="$(arg world)"/>
<!-- Always start in paused mode, and only unpause when spawning the model -->
<arg name="paused" value="true"/>
<arg name="gui" value="$(eval not arg('headless'))"/>
<arg name="use_sim_time" value="true"/>
Expand All @@ -51,23 +52,13 @@

<param name="m_ee" value="0.76" if="$(arg use_gripper)" />

<arg name="unpause" value="$(eval '' if arg('paused') else '-unpause')" />
<node name="$(arg arm_id)_model_spawner"
pkg="gazebo_ros"
type="spawn_model"
if="$(arg paused)"
args="-param robot_description -urdf -model $(arg arm_id)
args="-param robot_description -urdf -model $(arg arm_id) $(arg unpause)
$(arg initial_joint_positions)
">
</node>
<node name="$(arg arm_id)_model_spawner"
pkg="gazebo_ros"
type="spawn_model"
unless="$(arg paused)"
args="-param robot_description -urdf -model $(arg arm_id) -unpause
$(arg initial_joint_positions)
">
</node>

"/>

<!-- Spawn required ROS controllers -->
<node pkg="controller_manager"
Expand All @@ -85,8 +76,6 @@
args="franka_state_controller $(arg controller)"
/>

<remap to="cartesian_impedance_example_controller/equilibrium_pose" from="equilibrium_pose" />

<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher">
<rosparam param="source_list">[franka_state_controller/joint_states, franka_gripper/joint_states] </rosparam>
Expand All @@ -104,6 +93,7 @@
type="interactive_marker.py"
if="$(eval arg('controller') == 'cartesian_impedance_example_controller')">
<param name="link_name" value="$(arg arm_id)_link0" />
<remap to="cartesian_impedance_example_controller/equilibrium_pose" from="equilibrium_pose" />
</node>

</group>
Expand Down
2 changes: 1 addition & 1 deletion franka_gazebo/test/launch/panda-gazebo.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<!-- || PandaRobot With Retrieval of Feasible Parameters Using || -->
<!-- || Penalty-Based Optimization || -->
<!-- || by: Claudio Gaz, Marco Cognetti, Alexander Oliva, || -->
<!-- || Paolo Robuffo Giordano,Alessandro de Lucaa third-party || -->
<!-- || Paolo Robuffo Giordano, Alessandro de Luca third-party || -->
<!-- =============================================================== -->
<link name="world"/>
<joint name="panda_joint_panda_mount" type="fixed">
Expand Down