Robotics StackExchange | Archived questions

ROS Pluging in model.sdf (Not Working)

Hi everyone,

I am trying to add ROS camera model to the gazebo model.Camera and mymodel are different models. Camera model sdf like below: image description

I start emptyworld.launch with a `roslaunch gazeboros empty_world.launchcommand.After that instert the camera model to the world.When I enter therostopic list` to the console ,I can see the topics about the camera. Also I can see the image in the Topic Visualization in Gazebo. Shortly everything is fine.

I added camera model to the mymodel like below;

<include>
  <uri>model://camera</uri>
  <pose>0.2 0 0.2 0 0 0</pose>
</include>
<joint name="camera_joint" type="fixed">
  <child>camera::link</child>
  <parent>plane::base_link</parent>
</joint>

and I start the emptyworld like above and then instert my model to the world.I do not get a any error during this operations.When I enter the rostopic list to the console also ı can see the topics.I do not see any image in the Topic Visualization.When I try to `rostopic echo /imageraw` I didn't see any message on the topic.When I add only camera model I saw.

What I am doing wrong!!! Thanks.

Asked by mertaskin on 2020-12-29 02:26:11 UTC

Comments

Kindly post the camera model.sdf as formatted text and the full mymodel. It would be easier for us to help

Asked by wongrufus on 2020-12-29 21:22:35 UTC

I added,I found something else. When I removed the imu sensor I saw the camera was working. but i can't fly without imu sensor. what could be the reason?

Asked by mertaskin on 2020-12-30 02:38:58 UTC

I think my issue about the update rate of the sensor. When I deleted updated rate of imu sensor, camera started publish message.It stops after few minutes later.What ı am missing?

Asked by mertaskin on 2020-12-30 04:36:26 UTC

Might want to check your CPU load if that's the case. Simulating certain sensors can take a toll on CPU. I have cases where simulating lidars makes lidar readings come in once every 10+ seconds. In your case, your imu sensor update rate of 1000 is prolly too high.

Asked by wongrufus on 2020-12-30 22:09:57 UTC

Answers

<?xml version="1.0"?>
<sdf version='1.5' xmlns:xacro='http://ros.org/wiki/xacro'>
  <model name='plane'><!--The model element defines a complete robot or any other physical object-->
    <pose>0 0 0.246 0 0 0</pose> <!--A position (x,y,z) and oriantation(roll,pitch yaw) with respect to the specified frame -->
    <!-- -->
    <link name='base_link'> <!--A physical link with inertia,collision and visual properties.A link must be a child of model,and any number of links may exist in a model-->        
      <pose>0 0 0 0 0 0</pose><!--A position (x,y,z) and oriantation(roll,pitch yaw) with respect to the specified frame -->
      <inertial><!-- inertial properties of the links -->
        <pose>0 0 0 0 0 0</pose> <!--this is the pose of the inertial reference frame,relative to the specified reference frame.The origin of the inertial reference frame needs to be at the center of gravity.The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia -->
        <mass>1.5</mass> <!--the mass of the link -->
        <inertia> <!--3*3 rotational inertia matrix.Because the rotational inertia matrix is symmetric only 6 above diagonal elements of this matrix are specified here,using the attributes below -->
          <ixx>0.197563</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.1458929</iyy>
          <iyz>0</iyz>
          <izz>0.1477</izz>
        </inertia>
      </inertial>
      <collision name='base_link_collision'> <!--The collision properties of a link .Note that this can be different from the visual properties of a likn,for example simpler collision models are often used to reduce computation time -->
        <pose>0 0 -0.07 0 0 0</pose> <!-- A position (x,y,z) and oriantation(roll,pitch,yaw) with respect to the specified frame -->
        <geometry><!-- the shape of the visual or collision object -->
          <box> <!--box shape -->
            <size>0.47 0.47 0.11</size> <!-- the three side lengths of the box.The origin of the box is in its geometric center(inside the center of the box) type vector3 -->
          </box>
        </geometry>
        <surface><!-- the surface parameters -->
          <contact>
            <ode> <!--ODE contact parameters -->
              <max_vel>10</max_vel> <!--maximum contact correction velocity truncation term -->
              <min_depth>0.01</min_depth> <!-- min allowable depth before contact correction impulse is applied -->
            </ode>
          </contact>
          <!--<friction>
            <ode/>
          </friction>-->
        </surface>
      </collision>
      <visual name='base_link_visual'><!-- The visual properties of the link.This element specifies the shape of the object for visualization purposes-->
        <pose>0.07 0 -0.08 0 0 0</pose><!-- a position and orientation with respect to the specified frame-->
        <geometry> <!-- The shape of the visual or collision object -->
          <mesh> <!--  mesh shape-->
            <scale>0.1 0.1 0.1</scale> <!--  scaling factor applied to the mesh -->
            <uri>model://plane/meshes/body.dae</uri> <!--mesh uri -->
          </mesh>
        </geometry>
        <material><!-- the materail of the visual element -->
          <script> <!--name of material from an installed script file This will override the color element if the script exists -->
            <name>Gazebo/Red</name> <!-- Name of the script within the script file -->
            <uri>__default__</uri><!-- uri of the material script file-->
          </script>
        </material>
      </visual>
      <gravity>1</gravity><!--if true the link is affected by gravity -->
      <velocity_decay/> <!--Exponental damping of the link velocity -->
      <self_collide>0</self_collide><!-- if true the link can collide with other links in the model.two links within a model will collede if link 1 self collide or link 2 self collide.Liks conneected by a joint will never collide -->
    </link>

    <link name='plane/gps_link'>
      <inertial>
          <pose>0 0 0 0 0 0</pose>
          <mass>0.015</mass>
          <inertia>
            <ixx>0.00001</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.00002</iyy>
            <iyz>0</iyz>
            <izz>0.00002</izz>
          </inertia>
        </inertial>
      <sensor name="gps_sensor" type="gps"> <!-- the sensor tag decribes the type and proerties of a sensor -->
        <pose>0 0 0  0 0 0</pose>
        <update_rate>10.0</update_rate> <!--the frequency at which the sensor data is generated.İf left unspecified the sensor will generate data every cycle -->
        <always_on>true</always_on> <!-- if true the sensor will always be updated according to the update rate-->
        <gps><!-- these elements are specific to the gps sensor -->
          <position_sensing> <!-- parameters related to gps position measurement -->
            <horizontal> <!-- noise parameters for horizontal position measurement,in units of meters-->
              <noise type="gaussian_quantized"><!--  the properties of a sensor noise model-->
                <mean>0</mean>
                <stddev>1</stddev><!--standart deviation of gaussian distribution -->
                <bias_mean>3</bias_mean>
                <bias_stddev>1</bias_stddev>
                <precision>0.5</precision>
              </noise>
            </horizontal>
            <vertical> <!-- noise parameters for vertical position measurement in units of meters -->
              <noise type="gaussian_quantized">
                <mean>0</mean>
                <stddev>1</stddev>
                <bias_mean>3</bias_mean>
                <bias_stddev>1</bias_stddev>
                <precision>1.0</precision>
              </noise>
            </vertical>
          </position_sensing>
          <velocity_sensing> <!--parameters related to gps position measurement -->
            <horizontal> <!--noise parameters for horizontal velocity measurement in units of m/s -->
              <noise type="gaussian_quantized">
                <mean>0</mean>
                <stddev>0.1</stddev>
                <bias_mean>0.1</bias_mean>
                <bias_stddev>0.1</bias_stddev>
                <precision>0.1</precision>
              </noise>
            </horizontal>
            <vertical> <!-- noise parameters for vertical velocity measurement in units of m/s -->
              <noise type="gaussian_quantized">
                <mean>0</mean>
                <stddev>0.2</stddev>
                <bias_mean>0.2</bias_mean>
                <bias_stddev>0.2</bias_stddev>
                <precision>0.2</precision>
              </noise>
            </vertical>
          </velocity_sensing>
        </gps>
      </sensor>
    </link>
    <link name='plane/imu_link'>
      <pose>0 0 0 0 0 0</pose>  <!--A position and orientation with respect to the specified frame-->
      <inertial>
          <pose>0 0 0 0 0 0</pose> <!--this is the pose of the inertial reference frame ,relative to the specified reference frame.The origin og the inertial reference frame needs to be at the center of gravity.The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia -->
        <mass>0.015</mass>
        <inertia> <!--3*3 rotational inertia matrix.Because the rotational inertia matrix is symmetric,only 6 above diagonal elemenets of this matrix are specified here,using the attributes below-->
          <ixx>1e-05</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1e-05</iyy>
          <iyz>0</iyz>
          <izz>1e-05</izz>
        </inertia>
      </inertial>
      <sensor name="imu_sensor" type="imu">
        <pose>0 0 0 3.141593 0 0</pose> <!--TODO 0 0 0 0 0 0 dı  -->
        <always_on>1</always_on>
        <update_rate>1000</update_rate>
      </sensor>
    </link>
    <!-- -->
    <joint name='plane/imu_joint' type='revolute'> <!-- a joint connections two links with kinematic and dynamic properties-->
      <child>plane/imu_link</child> <!-- name of the child link -->
      <parent>base_link</parent> <!-- name of the parent link -->
      <axis><!--  parameters related to the axis of rotation for revolute joints,the axis of translation for prismatic joints-->
        <xyz>1 0 0</xyz> <!-- TODO delta wing ile karşılastır; represents the x,y,z components of this axis unit vector .This axis is expressed in the joint frame unless the use_parent_model_frame flag is set to true.The vector should be normalized-->
        <limit> <!--  specifies the limits of this joints-->
          <lower>0</lower> <!-- an attirube speciftying the lower joint limit(radians for revolute).Omit if joint is continuous -->
          <upper>0</upper><!-- an attirube speciftying the lower joint limit(radians for revolute).Omit if joint is continuous-->
          <effort>0</effort><!--an attribute for enforcing the max joint effort applied by joint::setforce limit is not enforced if value is negative -->
          <velocity>0</velocity><!-- an attribute for enforcing the max joint velocity -->
        </limit>
        <dynamics> <!--  an element specifying physical properties of the joint.These values are used to specify modeling properties of the joint,particularly useful for sim.-->
          <spring_reference>0</spring_reference><!--the spring reference position for this joint -->
          <spring_stiffness>0</spring_stiffness><!-- the spring stiffness for this joint axis -->
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame><!--flag to interpret the axis xyz element in the parent model frame  instead of joint frame. -->
      </axis>
    </joint>

    <link name='rotor_puller'>
      <pose>0.3 0 0.0 0 1.57 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.005</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000166704</iyy>
          <iyz>0</iyz>
          <izz>0.000167604</izz>
        </inertia>
      </inertial>
      <collision name='rotor_puller_collision'>
        <pose>0.0 0 0.0 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.1</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_puller_visual'>
        <pose>0 0 -0.09 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://plane/meshes/iris_prop_ccw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
    <joint name='rotor_puller_joint' type='revolute'>
      <child>rotor_puller</child>
      <parent>base_link</parent>
      <axis>
        <xyz>1 0 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>

    <link name="left_elevon">
      <inertial>
        <mass>0.00000001</mass>
        <inertia>
          <ixx>0.000001</ixx>
          <ixy>0.0</ixy>
          <iyy>0.000001</iyy>
          <ixz>0.0</ixz>
          <iyz>0.0</iyz>
          <izz>0.000001</izz>
        </inertia>
        <pose>0 0.3 0 0.00 0 0.0</pose>
      </inertial>
      <visual name='left_elevon_visual'>
        <pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
        <geometry>
          <mesh>
            <scale>0.1 0.1 0.1</scale>
            <uri>model://plane/meshes/left_aileron.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
    </link>
    <link name="right_elevon">
      <inertial>
        <mass>0.00000001</mass>
        <inertia>
          <ixx>0.000001</ixx>
          <ixy>0.0</ixy>
          <iyy>0.000001</iyy>
          <ixz>0.0</ixz>
          <iyz>0.0</iyz>
          <izz>0.000001</izz>
        </inertia>
        <pose>0 -0.3 0 0.00 0 0.0</pose>
      </inertial>
      <visual name='right_elevon_visual'>
        <pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
        <geometry>
          <mesh>
            <scale>0.1 0.1 0.1</scale>
            <uri>model://plane/meshes/right_aileron.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
    </link>
    <link name="elevator">
      <inertial>
        <mass>0.00000001</mass>
        <inertia>
          <ixx>0.000001</ixx>
          <ixy>0.0</ixy>
          <iyy>0.000001</iyy>
          <ixz>0.0</ixz>
          <iyz>0.0</iyz>
          <izz>0.000001</izz>
        </inertia>
        <pose> -0.5 0 0 0.00 0 0.0</pose>
      </inertial>
      <visual name='elevator_visual'>
        <pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
        <geometry>
          <mesh>
            <scale>0.1 0.1 0.1</scale>
            <uri>model://plane/meshes/elevators.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
    </link>
    <link name="rudder">
      <inertial>
        <mass>0.00000001</mass>
        <inertia>
          <ixx>0.000001</ixx>
          <ixy>0.0</ixy>
          <iyy>0.000001</iyy>
          <ixz>0.0</ixz>
          <iyz>0.0</iyz>
          <izz>0.000001</izz>
        </inertia>
        <pose>-0.5 0 0.05 0 0 0 </pose>
      </inertial>
      <visual name='rudder_visual'>
        <pose>0.07 0.0 -0.08 0.00 0 0.0</pose>
        <geometry>
          <mesh>
            <scale>0.1 0.1 0.1</scale>
            <uri>model://plane/meshes/rudder.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>__default__</uri>
          </script>
        </material>
      </visual>
    </link>
    <joint name='left_elevon_joint' type='revolute'>
      <parent>base_link</parent>
      <child>left_elevon</child>
      <pose>-0.07 0.4 0.08 0.00 0 0.0</pose>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <!-- -30/+30 deg. -->
          <lower>-0.53</lower>
          <upper>0.53</upper>
        </limit>
        <dynamics>
          <damping>1.000</damping>
        </dynamics>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>
    <joint name='right_elevon_joint' type='revolute'>
      <parent>base_link</parent>
      <child>right_elevon</child>
      <pose>-0.07 -0.4 0.08 0.00 0 0.0</pose>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <!-- -30/+30 deg. -->
          <lower>-0.53</lower>
          <upper>0.53</upper>
        </limit>
        <dynamics>
          <damping>1.000</damping>
        </dynamics>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>

    <joint name='elevator_joint' type='revolute'>
      <parent>base_link</parent>
      <child>elevator</child>
      <pose> -0.5 0 0 0 0 0</pose>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <!-- -30/+30 deg. -->
          <lower>-0.53</lower>
          <upper>0.53</upper>
        </limit>
        <dynamics>
          <damping>1.000</damping>
        </dynamics>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>
    <joint name='rudder_joint' type='revolute'>
      <parent>base_link</parent>
      <child>rudder</child>
      <pose>-0.5 0 0.05 0.00 0 0.0</pose>
      <axis>
        <xyz>0 0 1</xyz> <!-- TODO standard_vtol.sdf ile karşılaştır-->
        <limit>
          <!-- -30/+30 deg. -->
          <lower>-0.53</lower>
          <upper>0.53</upper>
        </limit>
        <dynamics>
          <damping>1.000</damping>
        </dynamics>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
      </physics>
    </joint>

    <plugin name="left_wing" filename="libLiftDragPlugin.so"> <!--a plugin is adynamically loaded chunk of code.İt can exist as a child of world,model and sensor -->
      <a0>0.05984281113</a0>
      <cla>4.752798721</cla>
      <cda>0.6417112299</cda>
      <cma>0.0</cma>
      <alpha_stall>0.3391428111</alpha_stall>
      <cla_stall>-3.85</cla_stall>
      <cda_stall>-0.9233984055</cda_stall>
      <cma_stall>0</cma_stall>
      <cp>-0.05 0.45 0.05</cp>
      <area>0.6</area>
      <air_density>1.2041</air_density>
      <forward>1 0 0</forward>
      <upward>0 0 1</upward>
      <link_name>base_link</link_name>
      <control_joint_name>
        left_elevon_joint
      </control_joint_name>
      <control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>
    </plugin>
    <plugin name="right_wing" filename="libLiftDragPlugin.so">
      <a0>0.05984281113</a0>
      <cla>4.752798721</cla>
      <cda>0.6417112299</cda>
      <cma>0.0</cma>
      <alpha_stall>0.3391428111</alpha_stall>
      <cla_stall>-3.85</cla_stall>
      <cda_stall>-0.9233984055</cda_stall>
      <cma_stall>0</cma_stall>
      <cp>-0.05 -0.45 0.05</cp>
      <area>0.6</area>
      <air_density>1.2041</air_density>
      <forward>1 0 0</forward>
      <upward>0 0 1</upward>
      <link_name>base_link</link_name>
      <control_joint_name>
        right_elevon_joint
      </control_joint_name>
      <control_joint_rad_to_cl>-0.5</control_joint_rad_to_cl>      
    </plugin>
    <plugin name="elevator" filename="libLiftDragPlugin.so">
      <a0>-0.2</a0>
      <cla>4.752798721</cla>
      <cda>0.6417112299</cda>
      <cma>0.0</cma>
      <alpha_stall>0.3391428111</alpha_stall>
      <cla_stall>-3.85</cla_stall>
      <cda_stall>-0.9233984055</cda_stall>
      <cma_stall>0</cma_stall>
      <cp>-0.5 0 0</cp>
      <area>0.01</area>
      <air_density>1.2041</air_density>
      <forward>1 0 0</forward>
      <upward>0 0 1</upward>
      <link_name>base_link</link_name>
      <control_joint_name>
        elevator_joint
      </control_joint_name>
      <control_joint_rad_to_cl>-4.0</control_joint_rad_to_cl>
    </plugin>
    <plugin name="rudder" filename="libLiftDragPlugin.so">
      <a0>0.0</a0>
      <cla>4.752798721</cla>
      <cda>0.6417112299</cda>
      <cma>0.0</cma>
      <alpha_stall>0.3391428111</alpha_stall>
      <cla_stall>-3.85</cla_stall>
      <cda_stall>-0.9233984055</cda_stall>
      <cma_stall>0</cma_stall>
      <cp>-0.5 0 0.05</cp>
      <area>0.02</area>
      <air_density>1.2041</air_density>
      <forward>1 0 0</forward>
      <upward>0 1 0</upward>
      <link_name>base_link</link_name>
      <control_joint_name> 
         rudder_joint 
      </control_joint_name> 
      <control_joint_rad_to_cl>4.0</control_joint_rad_to_cl>
    </plugin>
    <plugin name="rotor_puller_blade_1" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>0.084 0 0</cp>
      <forward>0 -1 0</forward>
      <upward>0 0 -1</upward>
      <link_name>rotor_puller</link_name>
    </plugin>
    <plugin name="rotor_puller_blade_2" filename="libLiftDragPlugin.so">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.2500</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.002</area>
      <air_density>1.2041</air_density>
      <cp>-0.084 0 0</cp>
      <forward>0 1 0</forward>
      <upward>0 0 -1</upward>
      <link_name>rotor_puller</link_name>
    </plugin>
    <plugin name="ardupilot_plugin" filename="libArduPilotPlugin.so">
      <fdm_addr>127.0.0.1</fdm_addr>
      <fdm_port_in>9002</fdm_port_in>
      <fdm_port_out>9003</fdm_port_out>
      <modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown>
      <gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
      <imuName>plane::plane/imu_link::imu_sensor</imuName>
      <connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
      <control channel="0">
          <multiplier>1</multiplier>
          <offset>-0.5</offset>
          <type>POSITION</type>
          <p_gain>2.5</p_gain>
          <i_gain>0.08</i_gain>
          <d_gain>0.07</d_gain>
          <i_max>1.7</i_max>
          <i_min>0</i_min>
          <cmd_max>1</cmd_max>
          <cmd_min>-1</cmd_min>
        <jointName>left_elevon_joint</jointName>
      </control>
      <control channel="1">
          <multiplier>1</multiplier>
          <offset>-0.5</offset>
          <type>POSITION</type>
          <p_gain>2.5</p_gain>
          <i_gain>0.08</i_gain>
          <d_gain>0.07</d_gain>
          <i_max>1.7</i_max>
          <i_min>0</i_min>
          <cmd_max>1</cmd_max>
          <cmd_min>-1</cmd_min>
        <jointName>right_elevon_joint</jointName>
      </control>
      <control channel="2">
          <multiplier>1</multiplier>
          <offset>-0.5</offset>
          <type>POSITION</type>
          <p_gain>2.5</p_gain>
          <i_gain>0.08</i_gain>
          <d_gain>0.07</d_gain>
          <i_max>1.7</i_max>
          <i_min>0</i_min>
          <cmd_max>1</cmd_max>
          <cmd_min>-1</cmd_min>
        <jointName>elevator_joint</jointName>
      </control>
      <control channel="3">
        <multiplier>1</multiplier>
        <offset>-0.5</offset>
          <type>POSITION</type>
          <p_gain>2.5</p_gain>
          <i_gain>0.08</i_gain>
          <d_gain>0.07</d_gain>
          <i_max>1.7</i_max>
          <i_min>0</i_min>
          <cmd_max>1</cmd_max>
          <cmd_min>-1</cmd_min>
        <jointName>rudder_joint</jointName>
      </control>
      <control channel="4">
        <multiplier>1000</multiplier>
        <offset>0</offset>
        <type>VELOCITY</type>
        <p_gain>10</p_gain>
        <i_gain>0</i_gain>
        <d_gain>0</d_gain>
        <i_max>0</i_max>
        <i_min>0</i_min>
        <cmd_max>20.0</cmd_max>
        <cmd_min>0.0</cmd_min>
        <jointName>rotor_puller_joint</jointName>
        <rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
      </control>
    </plugin>
    <static>0</static>
    <include>
      <uri>model://camera</uri>
      <pose>0.2 0 0.2 0 0 0</pose>
    </include>
    <joint name="camera_joint" type="fixed">
      <child>camera::link</child>
      <parent>plane::base_link</parent>
    </joint>
  </model>
</sdf>



<?xml version="1.0" ?>
<sdf version="1.5">
  <model name="camera">
    <pose>0 0 0.05 0 0 0</pose>
    <link name="link">
      <inertial>
        <mass>0.1</mass>
        <inertia>
          <ixx>0.000166667</ixx>
          <iyy>0.000166667</iyy>
          <izz>0.000166667</izz>
        </inertia>
      </inertial>
      <collision name="collision">
        <geometry>
          <box>
            <size>0.1 0.1 0.1</size>
          </box>
        </geometry>
      </collision>
      <visual name="visual">
        <geometry>
          <box>
            <size>0.1 0.1 0.1</size>
          </box>
        </geometry>
      </visual>
      <sensor name="camera" type="camera">
        <camera>
          <pose> 0 0 0 0 0 0</pose>
          <horizontal_fov>1.047</horizontal_fov>
          <image>
            <width>320</width>
            <height>240</height>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
        </camera>
        <plugin name="camera_plugin" filename="libgazebo_ros_camera.so">
            <alwaysOn>true</alwaysOn>
            <imageTopicName>image_raw</imageTopicName>
            <cameraInfoTopicName>camera_info</cameraInfoTopicName>
            <updateRate>30.0</updateRate>
            <cameraName>usb_cam</cameraName>
            <frameName>/robot_camera_link</frameName>
            <CxPrime>320.5</CxPrime>
            <Cx>320.5</Cx>
            <Cy>240.5</Cy>
            <hackBaseline>0</hackBaseline>
            <focalLength>320.000101</focalLength>
            <distortionK1>0.0</distortionK1>
            <distortionK2>0.0</distortionK2>
            <distortionK3>0.0</distortionK3>
            <distortionT1>0.0</distortionT1>
            <distortionT2>0.0</distortionT2>
        </plugin>
        <always_on>1</always_on>
        <update_rate>0</update_rate>
        <visualize>true</visualize>
      </sensor>
    </link>
  </model>
</sdf>

Asked by mertaskin on 2020-12-30 00:36:14 UTC

Comments

Pertaining to common FAQ etiquette, it is preferrable to edit the original question to provide additional information, instead of posting the additional information as an answer

Asked by wongrufus on 2020-12-30 22:10:50 UTC