ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Just a follow up for people who are interested:


<joint name="pan_joint" type="fixed">

<axis xyz="0 1 0" />
<origin xyz="0.5 0 0.5" rpy="0 0 0"/><!-- 1.5708-->
<parent link="base_link"/>
<child link="pan_link"/>

</joint>

<joint name="camera_joint" type="revolute"> <axis xyz="0 0 1"/> <limit lower="-${M_PI/2}" upper="${M_PI/2}" effort="50" velocity="1"/> <origin xyz="0.0 0 0.08" rpy="0 0 0"/> <parent link="pan_link"/> <child link="camera_link"/> </joint>

<link name="pan_link"> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.16 0.16 0.01"/> </geometry> </collision> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.02 0.02 0.01"/> </geometry>

<!--material>
     <script>Gazebo/Black</script>
</material-->

    <!--material name="Green"/--> <!-- i don t think the materials are initialized or something -->

</visual>
<inertial>
  <mass value="1e-5" />
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>

</link> <gazebo reference="pan_link"> <material>Gazebo/Yellow</material> </gazebo>

<link name="camera_link"> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.05 0.05 0.05"/> </geometry> </collision>

<visual>
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <geometry>
<box size="0.05 0.05 0.05"/>
  </geometry>
    <!--material>
        <script>
          <uri>file://media/materials/scripts/gazebo.material</uri>
          <name>Gazebo/Black</name>
        </script>
    </material-->

<!--material>
     <script>Gazebo/Black</script>
</material-->

    <!--material name="Green"/--> <!-- i don t think the materials are initialized or something -->

</visual>


<inertial>
  <mass value="1e-5" />
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>

</link> <gazebo reference="camera_link"> <material>Gazebo/Red</material> </gazebo>

<transmission name="pan_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="camera_joint"/> <actuator name="camera_pan_unit"> <hardwareinterface>EffortJointInterface</hardwareinterface> <mechanicalreduction>1</mechanicalreduction> </actuator> </transmission>

<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotnamespace>/aircobot</robotnamespace> </plugin> </gazebo>


Obviously you can do the same for the tilt joint Good luck, Marcus

Just a follow up for people who are interested:


<!-- camera -->
<!-- i think the pan joint can be deleted-->
<joint name="pan_joint" type="fixed">

type="fixed">

    <axis xyz="0 1 0" />
 <origin xyz="0.5 0 0.5" rpy="0 0 0"/><!-- 1.5708-->
 <parent link="base_link"/>
 <child link="pan_link"/>

</joint>

</joint> <joint name="camera_joint" type="revolute"> <axis xyz="0 0 1"/> 1" /> <limit lower="-${M_PI/2}" upper="${M_PI/2}" effort="50" velocity="1"/> <origin xyz="0.0 0 0.08" rpy="0 0 0"/> <parent link="pan_link"/> <child link="camera_link"/> </joint>

</joint> <link name="pan_link"> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.16 0.16 0.01"/> </geometry> </collision> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.02 0.02 0.01"/> <!-- 0.16 0.16 0.01 --> </geometry>

<!--material>
            <script>
              <uri>file://media/materials/scripts/gazebo.material</uri>
              <name>Gazebo/Black</name>
            </script>
        </material-->

    <!--material>
         <script>Gazebo/Black</script>
 </material-->

     <!--material name="Green"/--> <!-- i don t think the materials are initialized or something -->

 </visual>
 <inertial>
   <mass value="1e-5" />
   <origin xyz="0 0 0" rpy="0 0 0"/>
   <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
 </inertial>

</link> <gazebo reference="pan_link"> <material>Gazebo/Yellow</material> </gazebo>

</gazebo> <link name="camera_link"> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.05 0.05 0.05"/> </geometry> </collision>

</collision>


    <visual>
   <origin xyz="0 0 0" rpy="0 0 0"/>
   <geometry>
 <box size="0.05 0.05 0.05"/>
   </geometry>
     <!--material>
         <script>
           <uri>file://media/materials/scripts/gazebo.material</uri>
           <name>Gazebo/Black</name>
         </script>
     </material-->

 <!--material>
      <script>Gazebo/Black</script>
 </material-->

     <!--material name="Green"/--> <!-- i don t think the materials are initialized or something -->

 </visual>


 <inertial>
   <mass value="1e-5" />
   <origin xyz="0 0 0" rpy="0 0 0"/>
   <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
 </inertial>

</link> <gazebo reference="camera_link"> <material>Gazebo/Red</material> </gazebo>

</gazebo> <transmission name="pan_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="camera_joint"/> <actuator name="camera_pan_unit"> <hardwareinterface>EffortJointInterface</hardwareinterface> <mechanicalreduction>1</mechanicalreduction> <hardwareInterface>EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission>

</transmission> <gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotnamespace>/aircobot</robotnamespace> <robotNamespace>/aircobot</robotNamespace><!--seems to work--> </plugin> </gazebo>

</gazebo>

Obviously you can do the same for the tilt joint Good luck, Marcus