VisualPlugin not loaded not constructed at all
Hi,
I have problems running a VisualPlugin. When I put its tag under the <visual> tag of a <link>, it seems that it is not read at all when launching gazebo (neither its constructor is called).
Putting the <plugin> tag under <model> or <world> makes the plugin costructor called and an error about uncorrect plugin type (as expected).
When commanding:
gzserver world/box.world --verbose
Nothing is printed about the plugin
I am using gazebo 9 installed with ROS melodic.
Thanks for any help!
world file:
<?xml version="1.0"?>
<sdf version="1.4">
<world name="default">
<!-- Ground Plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="box">
<pose>0 0 5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<!-- Not Costructed at all -->
<plugin name="visualize_forces" filename="libvisualize_forces.so"/>
</visual>
</link>
<!-- Costructed, but not loaded, and immediately destroyed (as expected) -->
<!-- <plugin name="visualize_forces" filename="libvisualize_forces.so"/>-->
</model>
<!-- Costructed, but not loaded, and immediately destroyed (as expected) -->
<!-- <plugin name="visualize_forces" filename="libvisualize_forces.so"/>-->
</world>
</sdf>
cpp:
#include <gazebo/common/common.hh>
#include <gazebo/rendering/Visual.hh>
#include <gazebo/rendering/rendering.hh>
#include <gazebo/msgs/msgs.hh>
namespace gazebo
{
class GZ_RENDERING_VISIBLE VisualizeForces : public VisualPlugin
{
public:
VisualizeForces() {gzmsg << "Constructor" << std::endl;}
virtual ~VisualizeForces() {gzmsg << "Destructor" << std::endl;}
void Init() override {gzmsg << "Init" << std::endl;}
void Load(rendering::VisualPtr _visual, sdf::ElementPtr _sdf ) override
{
gzmsg << "Load" << std::endl;
}
};
GZ_REGISTER_VISUAL_PLUGIN(VisualizeForces)
}
I attach the files
C:\fakepath\VisualizeForces.cpp
Fast CmakeLists.txt:
cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
find_package(gazebo REQUIRED)
include_directories(${GAZEBO_INCLUDE_DIRS})
link_directories(${GAZEBO_LIBRARY_DIRS})
list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}")
add_library(visualize_forces SHARED src/VisualizeForces.cpp)
target_link_libraries(visualize_forces ${GAZEBO_LIBRARIES})