Minimal Class to create a VisualPlugin
I want to create a VisualPlugin , I tried following the tutorial in the gazebo website , which uses a WorldPlugin , and going along those lines I created the following class
#include <gazebo/common/Plugin.hh>
#include <gazebo/rendering/Visual.hh>
namespace gazebo
{
class GZ_PLUGIN_VISIBLE WorldPluginTutorial : public VisualPlugin
{
public: WorldPluginTutorial()
{
printf("Hello World!\n");
}
public: virtual void Load(rendering::VisualPtr _visual,
sdf::ElementPtr _sdf)
{
printf("loaded!");
if (!_visual || !_sdf)
{
gzerr << "No visual or SDF element specified. Plugin won't load." <<
std::endl;
return;
}
}
/* following the model shown in the basic plugin tutorial in the gazebo website
public: void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf)
{
printf("Loaded!\n");
}
*/
};
GZ_REGISTER_VISUAL_PLUGIN(WorldPluginTutorial)
}
which creates libgazebolineplugin.so shared library However the Load() function does not seem to be working, It prints Hello World! and then does nothing.
I used the following sdf file a part of blink_visual.world
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="box_sim">
<pose>0 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>
<plugin name="gazebo_line_plugin" filename="libgazebo_line_plugin.so">
<color_a>1 0 0 1</color_a>
<color_b>1 0 0 0</color_b>
<period>10</period>
</plugin>
</visual>
</link>
</model>
</world>
</sdf>
I would really appreciate it if someone told me what I was doing wrong , and how I can correct it.
Asked by ihateros on 2021-08-01 11:58:04 UTC
Answers
Is the missing of "\n"
at the end of printf("loaded!");
the cause?
Asked by Veerachart on 2021-08-04 02:01:07 UTC
Comments