lis-epfl / vswarm

vswarm: A ROS package to simulate and deploy vision-based drone swarms
MIT License
62 stars 22 forks source link

[Err] [Model.cc:1108] Model[drone_1] is attempting to load a plugin, but detected an incorrect plugin type. Plugin filename [libgazebo_gps_plugin.so] name[gps_plugin] #3

Open MUCHWAY opened 2 years ago

MUCHWAY commented 2 years ago

my question is:

When I run: roslaunch vswarm vswarm_gazebo.launch n:=3 ,I get an error:

[Err] [Model.cc:1108] Model[drone_1] is attempting to load a plugin, but detected an incorrect plugin type. Plugin filename[libgazebo_gps_plugin.so] name[gps_plugin]

/opt/ros/melodic/lib/gazebo_ros/gzserver:line 41: 20946 segfault (core dumped) GAZEBO_MASTER_URI="$desired_master_uri" GAZEBO_MODEL_DATABASE_URI="$desired_model_database_uri" gzserver $final

The error is that the gps_plugin is incorrect. After investigation, I found that the problem is:

vswarm_ws/src/vswarm/models/lequad/urdf/lequad_base.xacro:line158:

<!-- Instantiate gps plugin. --> <xacro:gps_plugin_macro namespace="${namespace}" gps_noise="true" > </xacro:gps_plugin_macro>

The gps_plugin location is at vswarm_ws/models/lequad/urdf/component_snippets.xacro:line127:

<xacro:macro name="gps_plugin_macro" params="namespace gps_noise"> <gazebo> <plugin name="gps_plugin" filename="libgazebo_gps_plugin.so"> <robotNamespace>${namespace}</robotNamespace> <gpsNoise>${gps_noise}</gpsNoise> </plugin> </gazebo> </xacro:macro>

I checked: First, the libgazebo_gps_plugin.so file exists, and I am sure it can be accessed (here I tested it with an absolute path) Then, I used the px4 official code to test: roslaunch px4 mavros_posix_sitl.launch, it can be used normally, no error is reported, and the same libgazebo_gps_plugin.so is also called here, so I am sure that it is no problem.

Then I checked the call to the gps_plugin in iris.sdf in px4 and found gps.sdf, So i changed the original gps_plugin to:

<xacro:macro name="gps_plugin_macro" params="namespace gps_noise"> <gazebo> <sensor name="gps" type="gps"> <plugin name="gps_plugin" filename="libgazebo_gps_plugin.so"> <robotNamespace>${namespace}</robotNamespace> <gpsNoise>${gps_noise}</gpsNoise> </plugin> </sensor> </gazebo> </xacro:macro>

After this run, there is no error, but the behavior is:

[ INFO] [1648804076.876074416, 28.036000000]: HP: requesting home position

this error keeps appearing,My guess is that the gps plugin is still not working correctly, I tried subscribing to the /drone_1/mavros/local_position/pose topic and nothing came up, so it is true that the gps_plugin is not working properly. Then I tried many methods without effect, so, I want to ask for help, this problem has been bothering me for days, if anyone can help me, thank you very much.

fabianschilling commented 2 years ago

PX4 can be quite verbose at times and HP: requesting home position only seems to be an info message. If you can successfully switch to position control (and you are fusing GPS) then I would say everything is working correctly.

MUCHWAY commented 2 years ago

@fabianschilling

This error doesn't just happen once or happens by accident, it happens constantly, like the following:

[ INFO] [1648865071.413654700, 180.776000000]: HP: requesting home position

[ INFO] [1648865085.361642477, 190.776000000]: HP: requesting home position

[ INFO] [1648865100.227298181, 200.776000000]: HP: requesting home position

[ INFO] [1648865116.611740218, 210.776000000]: HP: requesting home position

[ INFO] [1648865131.810260525, 220.776000000]: HP: requesting home position

[ INFO] [1648865146.680186603, 230.776000000]: HP: requesting home position

I switched the aircraft's mode to position according to your suggestion, and an error occurred:

INFO [tone_alarm] notify negative

I've tried subscribing to the topic of location in mavros,such as /drone_1/mavros/local_position/pose, but got nothing, so the problem should be that the gps plugin is not working properly.

And, whenrelative_localization_node.launch is started at this time, an error will also occur.

My problem is described in detail in the previous article, if you can, please help me analyze it.

fabianschilling commented 2 years ago

The fact that you had to wrap <plugin> with another <sensor> tag to suppress the error suggests that there is a version mismatch somewhere. Are you using these Gazebo (9.16.0) and PX4 (v1.10.2) versions? I recall that the SDF/URDF description of drones/sensors changed quite frequently between releases. I re-read your edited question but unfortunately I can not debug the problem effectively with the limited information. If you say that roslaunch px4 mavros_posix_sitl.launch works fine, try to diff the robot descriptions of the PX4 repo and the ones I'm using and fix potential differences.

lithiumhydride2 commented 1 year ago

any update?i met same problem

calmelo commented 1 year ago

@fabianschilling

This error doesn't just happen once or happens by accident, it happens constantly, like the following:

[ INFO] [1648865071.413654700, 180.776000000]: HP: requesting home position

[ INFO] [1648865085.361642477, 190.776000000]: HP: requesting home position

[ INFO] [1648865100.227298181, 200.776000000]: HP: requesting home position

[ INFO] [1648865116.611740218, 210.776000000]: HP: requesting home position

[ INFO] [1648865131.810260525, 220.776000000]: HP: requesting home position

[ INFO] [1648865146.680186603, 230.776000000]: HP: requesting home position

I switched the aircraft's mode to position according to your suggestion, and an error occurred:

INFO [tone_alarm] notify negative

I've tried subscribing to the topic of location in mavros,such as /drone_1/mavros/local_position/pose, but got nothing, so the problem should be that the gps plugin is not working properly.

And, whenrelative_localization_node.launch is started at this time, an error will also occur.

My problem is described in detail in the previous article, if you can, please help me analyze it.

Have you resolve the problem? I meet the problem too. However, roslaunch px4 mavros_posix_sitl.launch can launch successfully, and there are gps data.

calmelo commented 1 year ago

I've tried subscribing to the topic of location in mavros,such as /drone_1/mavros/local_position/pose, but got nothing, so the problem should be that the gps plugin is not working properly.

I have Gazebo9.19.0 + px4 1.10.2, I can't get gps information by running the code. However, roslaunch px4 mavros_posix_sitl.launch can obtain the gps data. How can I resolve the problem? I will appreciate it if you can help me. Thanks!

MUCHWAY commented 1 year ago

I jump this problem by changing position source form gps to mocap。

calmelo commented 1 year ago

I jump this problem by changing position source form gps to mocap。

However, "vswarm takeoff" rely on the gps? If you use the mocap, can you run "vswarm takeoff" successfully?

MUCHWAY commented 1 year ago

yes, the "vswarm takeoff" can't be used, so I modified the takeoff by writing a script in python to send commands to the drone and QGroundControl to send takeoff commands.

calmelo commented 1 year ago

yes, the "vswarm takeoff" can't be used, so I modified the takeoff by writing a script in python to send commands to the drone and QGroundControl to send takeoff commands.

Can you share me the takeoff script? Thanks!

lithiumhydride2 commented 1 year ago

I fix this bug by change the code block in component_snippets.xacro:

  <xacro:macro name="gps_plugin_macro" params="namespace gps_noise">
    <gazebo>
      <plugin name="gps_plugin" filename="libgazebo_gps_plugin.so">
        <robotNamespace>${namespace}</robotNamespace>
        <gpsNoise>${gps_noise}</gpsNoise>
      </plugin>
    </gazebo>
  </xacro:macro>

into some code form px4_iris:

 <xacro:macro name="gps_plugin_macro" params="namespace gps_noise">
    <gazebo>
      <model name='gps0'>
        <link name='link'>
          <pose>0 0 0 0 0 0</pose>
          <inertial>
            <pose>0 0 0 0 0 0</pose>
            <mass>0.01</mass>
            <inertia>
              <ixx>2.1733e-06</ixx>
              <ixy>0</ixy>
              <ixz>0</ixz>
              <iyy>2.1733e-06</iyy>
              <iyz>0</iyz>
              <izz>1.8e-07</izz>
            </inertia>
          </inertial>
          <visual name='visual'>
            <geometry>
              <cylinder>
                <radius>0.01</radius>
                <length>0.002</length>
              </cylinder>
            </geometry>
            <material>
              <script>
                <name>Gazebo/Black</name>
                <uri>__default__</uri>
              </script>
            </material>
          </visual>

          <sensor name="gps" type="gps">
            <pose>0 0 0 0 0 0</pose>
            <plugin name="gps_plugin" filename="libgazebo_gps_plugin.so">
              <robotNamespace>${namespace}</robotNamespace>
              <gpsNoise>${gps_noise}</gpsNoise>
              <gpsXYRandomWalk>2.0</gpsXYRandomWalk>
              <gpsZRandomWalk>4.0</gpsZRandomWalk>
              <gpsXYNoiseDensity>0.0002</gpsXYNoiseDensity>
              <gpsZNoiseDensity>0.0004</gpsZNoiseDensity>
              <gpsVXYNoiseDensity>0.2</gpsVXYNoiseDensity>
              <gpsVZNoiseDensity>0.4</gpsVZNoiseDensity>
            </plugin>
          </sensor>
        </link>
      </model>
    </gazebo>

And vswarm takeoff works fine !

calmelo commented 12 months ago

I fix this bug by change the code block in component_snippets.xacro:

  <xacro:macro name="gps_plugin_macro" params="namespace gps_noise">
    <gazebo>
      <plugin name="gps_plugin" filename="libgazebo_gps_plugin.so">
        <robotNamespace>${namespace}</robotNamespace>
        <gpsNoise>${gps_noise}</gpsNoise>
      </plugin>
    </gazebo>
  </xacro:macro>

into some code form px4_iris:

 <xacro:macro name="gps_plugin_macro" params="namespace gps_noise">
    <gazebo>
      <model name='gps0'>
        <link name='link'>
          <pose>0 0 0 0 0 0</pose>
          <inertial>
            <pose>0 0 0 0 0 0</pose>
            <mass>0.01</mass>
            <inertia>
              <ixx>2.1733e-06</ixx>
              <ixy>0</ixy>
              <ixz>0</ixz>
              <iyy>2.1733e-06</iyy>
              <iyz>0</iyz>
              <izz>1.8e-07</izz>
            </inertia>
          </inertial>
          <visual name='visual'>
            <geometry>
              <cylinder>
                <radius>0.01</radius>
                <length>0.002</length>
              </cylinder>
            </geometry>
            <material>
              <script>
                <name>Gazebo/Black</name>
                <uri>__default__</uri>
              </script>
            </material>
          </visual>

          <sensor name="gps" type="gps">
            <pose>0 0 0 0 0 0</pose>
            <plugin name="gps_plugin" filename="libgazebo_gps_plugin.so">
              <robotNamespace>${namespace}</robotNamespace>
              <gpsNoise>${gps_noise}</gpsNoise>
              <gpsXYRandomWalk>2.0</gpsXYRandomWalk>
              <gpsZRandomWalk>4.0</gpsZRandomWalk>
              <gpsXYNoiseDensity>0.0002</gpsXYNoiseDensity>
              <gpsZNoiseDensity>0.0004</gpsZNoiseDensity>
              <gpsVXYNoiseDensity>0.2</gpsVXYNoiseDensity>
              <gpsVZNoiseDensity>0.4</gpsVZNoiseDensity>
            </plugin>
          </sensor>
        </link>
      </model>
    </gazebo>

And vswarm takeoff works fine !

Thanks, I can takeoff successfully now! However, when I run "vswarm offboard", the uav has no movement. Did you run the project successfully? If you run "vswarm offboard", can the uav have movement? I'm looking forward to your reply. Thanks!

lithiumhydride2 commented 12 months ago

HI, I ran this project successfully, after command "vswarm offboard", drones began to flock. Some tips for you to check: