<joint name="sonar_forward_left_joint" type="fixed">
<parent link="mounting_plate"/>
<child link="sonar_forward_left"/>
- <origin xyz="0.115 0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
+ <origin xyz="0.115 0.05 -0.012" rpy="0 ${-10*PI/180} 0"/>
</joint>
<joint name="sonar_forward_right_joint" type="fixed">
<parent link="mounting_plate"/>
<child link="sonar_forward_right"/>
- <origin xyz="0.115 -0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
+ <origin xyz="0.115 -0.05 -0.012" rpy="0 ${-10*PI/180} 0"/>
</joint>
<joint name="sonar_backward_joint" type="fixed">
<parent link="mounting_plate"/>
<child link="sonar_backward"/>
- <origin xyz="-0.115 0.0 -0.012" rpy="0 ${-175*PI/180} 0"/>
+ <origin xyz="-0.115 0.0 -0.012" rpy="0 ${-170*PI/180} 0"/>
</joint>
<joint name="ir_left_joint" type="fixed">