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

Enabling non-namespace use of Gazebo robot #187

Closed
wants to merge 4 commits into from
Closed
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
4 changes: 2 additions & 2 deletions franka_description/robots/dual_panda_example.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,11 @@
</link>

<!-- right arm with gripper -->
<xacro:panda_arm arm_id="$(arg arm_id_1)" connected_to="base" xyz="0 -0.5 1" safety_distance="0.03"/>
<xacro:panda_arm arm_id="$(arg arm_id_1)" ns="$(arg arm_id_1)" connected_to="base" xyz="0 -0.5 1" safety_distance="0.03" />
<xacro:hand ns="$(arg arm_id_1)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_1)_link8" safety_distance="0.03"/>

<!-- left arm with gripper -->
<xacro:panda_arm arm_id="$(arg arm_id_2)" connected_to="base" xyz="0 0.5 1" safety_distance="0.03"/>
<xacro:panda_arm arm_id="$(arg arm_id_2)" ns="$(arg arm_id_2)" connected_to="base" xyz="0 0.5 1" safety_distance="0.03" />
<xacro:hand ns="$(arg arm_id_2)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_2)_link8" safety_distance="0.03"/>

</robot>
4 changes: 3 additions & 1 deletion franka_description/robots/panda_arm.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
<xacro:arg name="hand" default="false" />
<!-- Is the robot being simulated in gazebo?" -->
<xacro:arg name="gazebo" default="false" />
<!-- Namespace of robot in Gazebo/ROS (default: empty) -->
<xacro:arg name="ns" default="" />

<xacro:unless value="$(arg gazebo)">
<!-- Create a URDF for a real hardware -->
Expand Down Expand Up @@ -61,7 +63,7 @@

<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>$(arg arm_id)</robotNamespace>
<robotNamespace>$(arg ns)</robotNamespace>
<controlPeriod>0.001</controlPeriod>
<robotSimType>franka_gazebo/FrankaHWSim</robotSimType>
</plugin>
Expand Down
63 changes: 4 additions & 59 deletions franka_gazebo/launch/panda.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
<?xml version="1.0"?>
<launch>
<arg name="ns" default="" doc="Namespace to launch the Gazebo robot in" />

<!-- Gazebo & GUI Configuration -->
<arg name="gazebo" default="true" doc="Should the gazebo simulation be launched? Use false in case if you want to include this file and launch gazebo yourself" />
Expand Down Expand Up @@ -37,66 +38,10 @@
<arg name="use_sim_time" value="true"/>
</include>

<group ns="$(arg arm_id)">
<param name="robot_description"
command="xacro $(find franka_description)/robots/panda_arm.urdf.xacro
gazebo:=true
hand:=$(arg use_gripper)
arm_id:=$(arg arm_id)
xyz:='$(arg x) $(arg y) $(arg z)'
rpy:='$(arg roll) $(arg pitch) $(arg yaw)'">
</param>

<rosparam file="$(find franka_gazebo)/config/franka_hw_sim.yaml" subst_value="true" />
<rosparam file="$(find franka_gazebo)/config/sim_controllers.yaml" subst_value="true" />

<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"
args="-param robot_description -urdf -model $(arg arm_id) $(arg unpause)
$(arg initial_joint_positions)
"/>

<!-- Spawn required ROS controllers -->
<node pkg="controller_manager"
type="spawner"
name="$(arg arm_id)_gripper_spawner"
if="$(arg use_gripper)"
args="franka_gripper"
respawn="false"
/>

<node pkg="controller_manager"
type="spawner"
name="$(arg arm_id)_controller_spawner"
respawn="false" output="screen"
args="franka_state_controller $(arg controller)"
/>

<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>
<param name="rate" value="30"/>
</node>
<node name="joint_state_desired_publisher" type="joint_state_publisher" pkg="joint_state_publisher">
<rosparam param="source_list">[franka_state_controller/joint_states_desired, franka_gripper/joint_states] </rosparam>
<param name="rate" value="30"/>
<remap from="joint_states" to="joint_states_desired" />
</node>

<!-- Start only if cartesian_impedance_example_controller -->
<node name="interactive_marker"
pkg="franka_example_controllers"
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>
<!-- Depending on whether the namespace is empty or not, don't start in a namespace (or do) -->
<include file="$(dirname)/panda_ns.launch.xml" pass_all_args="true" if="$(eval arg('ns') == '')" />
<include file="$(dirname)/panda_ns.launch.xml" pass_all_args="true" if="$(eval arg('ns') != '')" ns="$(arg ns)" />

<node pkg="rviz" type="rviz" output="screen" name="rviz" args="-d $(find franka_gazebo)/config/franka_sim_description_with_marker.rviz" if="$(arg rviz)"/>

Expand Down
71 changes: 71 additions & 0 deletions franka_gazebo/launch/panda_ns.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
<?xml version="1.0"?>
<launch>

<!-- This is a helper launch file for panda.launch
As roslaunch doesn't allow for empty ns arguments and to avoid code duplication,
we factored out code here that should run either in or out a namespace.
All arguments are simply inherited from the parent launch file.
-->
<param name="robot_description"
command="xacro $(find franka_description)/robots/panda_arm.urdf.xacro
gazebo:=true
hand:=$(arg use_gripper)
arm_id:=$(arg arm_id)
ns:=$(arg ns)
xyz:='$(arg x) $(arg y) $(arg z)'
rpy:='$(arg roll) $(arg pitch) $(arg yaw)'">
</param>

<rosparam file="$(find franka_gazebo)/config/franka_hw_sim.yaml" subst_value="true" />
<rosparam file="$(find franka_gazebo)/config/sim_controllers.yaml" subst_value="true" />

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

<!-- Avoid node names of the form arm_id/arm_id_xxx. Use arm_id/xxx instead. -->
<arg name="node_prefix" value="$(eval '' if arg('ns') == arg('arm_id') else arg('arm_id') + '_')" />

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

<!-- Spawn required ROS controllers -->
<node pkg="controller_manager"
type="spawner"
name="$(arg node_prefix)gripper_spawner"
if="$(arg use_gripper)"
args="franka_gripper"
respawn="false"
/>

<node pkg="controller_manager"
type="spawner"
name="$(arg node_prefix)controller_spawner"
respawn="false" output="screen"
args="franka_state_controller $(arg controller)"
/>

<node name="$(arg node_prefix)robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="$(arg node_prefix)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>
<param name="rate" value="30"/>
</node>
<node name="$(arg node_prefix)joint_state_desired_publisher" type="joint_state_publisher" pkg="joint_state_publisher">
<rosparam param="source_list">[franka_state_controller/joint_states_desired, franka_gripper/joint_states] </rosparam>
<param name="rate" value="30"/>
<remap from="joint_states" to="joint_states_desired" />
</node>

<!-- Start only if cartesian_impedance_example_controller -->
<node name="$(arg node_prefix)cartesian_goal_marker"
pkg="franka_example_controllers"
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>

</launch>