URDF joints not appearing in Gazebo
I have a URDF model (defined in a .xacro file) of a UUV, and I am trying to enable the robot to be controllable via ROS. I believe my issue lies on the Gazebo side, which is why I'm asking this here.
Here is a snippet of my URDF:
<joint name="base_to_physics" type="fixed">
<parent link="base_link"/>
<child link="base_link_physics"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 1" />
<dynamics damping="0.7"/>
</joint>
<joint name="base_to_sonar" type="fixed">
<parent link="base_link_physics"/>
<child link="sonar"/>
<origin rpy="0 ${-pi/2} ${-pi/2}" xyz="${l4_length/2} ${-((l4_width/2)-sonar_radius-l4_vframe_width)} ${-(-l4_top_height -((l4_height - l4_top_height)/2))}"/>
</joint>
<joint name="base_to_camera" type="fixed">
<parent link="base_link_physics"/>
<child link="camera"/>
<origin rpy="${pi} ${-pi/2} 0" xyz="${l4_length/2} ${(l4_width/2)-sonar_radius-l4_vframe_width} ${l4_top_height+((l4_height - l4_top_height)/2)-camera_lens_center_offset}"/>
</joint>
<joint name="base_to_imu" type="fixed">
<parent link="base_link_physics"/>
<child link="imu"/>
<origin rpy="0 0 0" xyz="0 ${(l4_width/2 - l4_width/6 - imu_width/2)} ${l4_top_height + imu_height/2}"/>
</joint>
<joint name="base_to_depth" type="fixed">
<parent link="base_link_physics"/>
<child link="depth_sensor"/>
<origin rpy="0 0 0" xyz="0 ${(-l4_width/2 + l4_width/6 + imu_width/2)} ${l4_top_height + imu_height/2}"/>
</joint>
However, when I launch gazebo in ROS using this command:
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model vector_l4" />
...then I get this error:
[ERROR] [1409750686.829834847, 2469.509000000]: This robot has a joint named "base_to_physics" which is not in the gazebo model.
What I notice, and this is what makes me think it's a gazebo problem, is that in the Gazebo visualizer, if I select the robot and go to View->Joints, then no joints appear in the "Joints" tab on the right side of the window.
The only other example of this problem that I've seen is on the ROS answers site, but I have already implemented the fix detailed therein and my issue remains.
So how can I get my URDF joints to show up in Gazebo? Am I missing a tag within my joint definitions? I'm using ROS Indigo Igloo and both gzclient and gzserver report version 4.0.1.