Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

When I look into your code, the gazebo_timepix plugin seem like a Model plugin, because it is placed dicectly inside the model tags. Whereas the gazebo_ros_camera plugin is a Sensor plugin. It is placed inside the sensor tags.

If you wish to attach the gazebo_timepix plugin to the timepix model in URDF description file you write:

<gazebo reference="timepix">
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

When I look into your code, the gazebo_timepix gazebo_timepix plugin seem seems like a Model plugin, plugin, because it is placed dicectly directly inside the model tags. Whereas the gazebo_ros_camera plugin plugin is a Sensor plugin. plugin. It is placed inside the sensor tags.

If you wish to attach the gazebo_timepix plugin to the timepix model in URDF description file you write:

<gazebo reference="timepix">
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

When I look into your code, the gazebo_timepix plugin seems like a Model plugin, because it is placed directly inside the model tags. Whereas the gazebo_ros_camera plugin is a Sensor plugin. It is placed inside the sensor tags.

If you wish to attach the gazebo_timepix gazebo_timepix plugin to the timepix model in URDF description file you write:

<gazebo reference="timepix">
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

When I look into your code, the gazebo_timepix plugin seems like a Model plugin, because it is placed directly inside the model tags. Whereas the gazebo_ros_camera plugin is a Sensor plugin. It is placed inside the sensor tags.

If you wish to attach the gazebo_timepix plugin to the timepix model in timepix URDF description file you write:

<gazebo reference="timepix">
<gazebo>
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

EDIT

There are various types of plugins (Model, Sensor, World, System, Visual) and those cannot be used the same way. The first thing you need to figure out is what type of plugin the timepix plugin is.

If it is the Model plugin, you can only use it by writing the lines shown below inside your URDF description of the robot you are attaching it to.

<gazebo>
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

This plugin gets pointer to the model and the sdf parameters you can specify inside the plugin description.

Load function for model plugin:

void MyModelPlugin::Load( physics::ModelPtr _parent,
                                sdf::ElementPtr _sdf)
    {...}

If it is some sensor plugin, you can only attach it to a sensor of appropriate type. So only if the Load function of this plugin look something like the code shown below, you can directly switch the plugin for the camera controller plugin in your example.

void MyCameraPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
    {
        ...
        CameraPlugin::Load(_parent,_sdf);
        ...
    }

You would write

<gazebo reference="camera_link">
    <sensor type="camera" name="camera1">
    <update_rate>30.0</update_rate>
    <camera name="head">
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
        <width>800</width>
        <height>800</height>
        <format>R8G8B8</format>
        </image>
        <clip>
        <near>0.02</near>
        <far>300</far>
        </clip>
        <noise>
        <type>gaussian</type>
        <mean>0.0</mean>
        <stddev>0.007</stddev>
        </noise>
    </camera>
    <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
    </sensor>
</gazebo>

If the plugin works attached to model like

<model name="timepix">
  <static>1</static>
  <link name="link">
    <pose>0 1.0 0.0 0 0 0</pose>
    <visual name="visual">
      <geometry>
        <box>
          <size>0.2 0.2 0.2</size>
        </box>
      </geometry>
    </visual>
  </link>
  <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</model>

It is a Model plugin and you have to use it as one.

When I look into your code, the gazebo_timepix plugin seems like a Model plugin, because it is placed directly inside the model tags. Whereas the gazebo_ros_camera plugin is a Sensor plugin. It is placed inside the sensor tags.

If you wish to attach the gazebo_timepix plugin to the timepix model in timepix URDF description file you write:

<gazebo>
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

EDIT

There are various types of plugins (Model, Sensor, World, System, Visual) and those cannot be used the same way. The first thing you need to figure out is what type of plugin the timepix plugin is.

If it is the Model plugin, you can only use it by writing the lines shown below inside your URDF description of the robot you are attaching it to.

<gazebo>
     <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</gazebo>

This plugin gets pointer to the model and the sdf parameters you can specify inside the plugin description.

Load function for model plugin:

void MyModelPlugin::Load( physics::ModelPtr _parent,
                                sdf::ElementPtr _sdf)
    {...}

If it is some sensor plugin, you can only attach it to a sensor of appropriate type. So only if the Load function of this plugin look something like the code shown below, you can directly switch the plugin for the camera controller plugin in your example.

void MyCameraPlugin::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
    {
        ...
        CameraPlugin::Load(_parent,_sdf);
        ...
    }

You would write

<gazebo reference="camera_link">
    <sensor type="camera" name="camera1">
    <update_rate>30.0</update_rate>
    <camera name="head">
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
        <width>800</width>
        <height>800</height>
        <format>R8G8B8</format>
        </image>
        <clip>
        <near>0.02</near>
        <far>300</far>
        </clip>
        <noise>
        <type>gaussian</type>
        <mean>0.0</mean>
        <stddev>0.007</stddev>
        </noise>
    </camera>
    <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
    </sensor>
</gazebo>

If the plugin works attached to model like

<model name="timepix">
  <static>1</static>
  <link name="link">
    <pose>0 1.0 0.0 0 0 0</pose>
    <visual name="visual">
      <geometry>
        <box>
          <size>0.2 0.2 0.2</size>
        </box>
      </geometry>
    </visual>
  </link>
  <plugin name="gazebo_timepix" filename="libgazebo_timepix.so"/>
</model>

It is a Model plugin and you have to use it as one.

one. The 'camera_link' must be a part of some model. So the timepix model plugin would go inside the description of this model.