You can wrap the xacro in your own model file, anchoring the gripper to a dummy link:
<?xml version="1.0"?>
<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
name="sdh" >
<!-- The following included files set up definitions of parts of the robot body -->
<!-- cob sdh-->
<include filename="$(find cob_description)/ros/urdf/sdh_v0/sdh.urdf.xacro" />
<!-- foot for arm-->
<link name="dummy_link">
<inertial>
<origin xyz="0 0 -10" rpy="0 0 0"/>
<mass value="1000.0"/>
<inertia ixx="100.0" ixy="0" ixz="0" iyy="100.0" iyz="0" izz="100.0" />
</inertial>
<visual>
<origin xyz="0 0 0.25" rpy="0 0 0" />
<geometry>
<box size="0.6 0.4 0.4"/>
<!--cylinder radius="0.1" length="0.5"/-->
</geometry>
<material name="Blue" />
</visual>
<collision>
<origin xyz="0 0 0.25" rpy="0 0 0" />
<geometry>
<box size="0.6 0.4 0.4"/>
<!--cylinder radius="0.1" length="0.5"/-->
</geometry>
</collision>
</link>
<!-- sdh -->
<xacro:cob_sdh_v0 name="sdh" parent="dummy_link">
<origin xyz="0 0 0" rpy="0 3.1415926 0" />
</xacro:cob_sdh_v0>
</robot>
save it as test.urdf.xacro
in your own ros package (my_own_foo_ros_pkg
).
Then construct a launch script to push the xacro file onto the parameter server:
<launch>
<!-- send pr2 urdf to param server -->
<param name="robot_description" command="$(find xacro)/xacro.py '$(find my_own_foo_ros_pkg)/test.urdf.xacro'" />
</launch>