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

Simulating a Camera with a Pan Tilt Unit

asked 2014-03-20 04:27:37 -0500

Marcus gravatar image

Hey there,

is there a simple way to have a pan tilt unit on my 4 wheeled robot (in simulation)? I have read some comments that indicated that this is possible in Gazebo, but I was not able to locate the correct plug-in. Perfect would be something like a pan tilt platform with a camera on top. However, for my tests it would suffice if I would be able to just turn the camera (so just pan - no tilt). So far I tried to use the "Planar Move Plug-in" on the camera_link, while still using the skid steering drive plug-in to move the robot, which resulted in the robot not being able to move anymore. I guess you cannot use those two plug-in's in one file.

Thanks for any suggestions. Marcus

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
4

answered 2014-03-20 05:17:40 -0500

It appears the old way of using a PR2 controller manager is deprecated and does not work anymore in hydro (Example of a roll/pitch mount using that approach here).

Everything you need to know for using the new ROS Control approach should be explained in the ROS Control with Gazebo tutorial. Essentially, you need a URDF model with 3 links (connected via two joints). If you setup the two joint axes as required for your pan/tilt unit and load the controllers as explained in the tutorial, things should work and you should be able to command the joints into desired positions.

edit flag offensive delete link more

Comments

Thx Stefan, I ll get started on that right away.

Marcus gravatar image Marcus  ( 2014-03-20 05:45:57 -0500 )edit

Hi Stefan, I have followed the tutorial, but now I cannot advance my work, because the controller cannot be loaded. ROS --> "controller type 'effort_controllers/JointPositionController' does not exist." Checking for the existing controller types the JointPositionController is not listed. Thx,Marcus

Marcus gravatar image Marcus  ( 2014-03-25 05:26:56 -0500 )edit

Ok, I haven´t tried that tutorial myself, so can´t really comment. Given that this a specific problem different from the original post, it might be a good idea to ask a separate question about this.

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2014-03-25 07:00:32 -0500 )edit

Will do, Thx again for the quick answer

Marcus gravatar image Marcus  ( 2014-03-25 07:26:56 -0500 )edit

Hi Marcus,

DId you ever get a pan/tilt camera working. If so, do you have code hosted anywhere? I'm trying to accomplish a similar task with a simulated Pioneer robot in Gazebo.

Craig Hay gravatar image Craig Hay  ( 2015-09-25 09:05:57 -0500 )edit

Hello Craig, in fact I did accomplish it. I introduced a new link/joint (e.g. pan_link/*joint). I set the joint type to revolute and found out how to move it through trial and error :). I do not host the code anywhere, but will try to upload the interesting parts of the urdf.xacro

Marcus gravatar image Marcus  ( 2015-09-28 11:10:26 -0500 )edit
2

answered 2015-09-28 11:13:32 -0500

Marcus gravatar image

updated 2015-09-28 11:14:02 -0500

Just a follow up for people who are interested:


<!-- camera -->
<!-- i think the pan joint can be deleted-->
<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"/> <!-- 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>





  <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><!--seems to work-->
  </plugin>
</gazebo>

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

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2014-03-20 04:27:37 -0500

Seen: 2,302 times

Last updated: Sep 28 '15