Last week, my plugins were working. Without having changed anything, this week the visual plugin crashes.
Here's the error:
gzclient: /usr/include/boost/smart_ptr/shared_ptr.hpp:653: typename boost::detail::sp_member_access<T>::type boost::shared_ptr<T>::operator->() const [with T = gazebo::rendering::Camera; typename boost::detail::sp_member_access<T>::type = gazebo::rendering::Camera*]: Assertion `px != 0' failed.
Aborted (core dumped)
Here are the only files necessary to reproduce the crash:
Visual plugin:
#include <gazebo/gazebo.hh>
#include <gazebo/common/common.hh>
#include <gazebo/rendering/rendering.hh>
#include <stdio.h>
namespace gazebo
{ class SpacenavVisualPlugin : public VisualPlugin
{ public:
// Constructor
SpacenavVisualPlugin() : VisualPlugin()
{ printf( "SpacenavVisualPlugin started\n" ); // DEBUG
}
// Destructor
~SpacenavVisualPlugin() // : ~VisualPlugin()
{ printf( "SpacenavVisualPlugin stopped\n" ); // DEBUG
}
void Load( rendering::VisualPtr _visual, sdf::ElementPtr /*_sdf*/)
{ // === Turn off the SpaceNavigator's default camera control
rendering::ScenePtr scene = _visual->GetScene();
rendering::UserCameraPtr cam = scene->GetUserCamera( 0 );
cam->SetJoyPoseControl( false );
cam->SetJoyTwistControl( false );
}
};
// Register this plugin with the simulator
GZ_REGISTER_VISUAL_PLUGIN( SpacenavVisualPlugin )
};
World file:
<?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 just to hold plugin that turns off spacenav camera control -->
<model name="dummy_model">
<link name="dummy">
<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="spacenavVisualPlugin" filename="/media/jason/Lexar/Code_samples/gazebo_plugin_tutorial/build/libspacenavVisualPlugin.so"/>
</visual>
</link>
</model>
</world>
</sdf>
The commands I run are gzserver test.world
and, in a separate terminal window, gzclient
.
Here is the question where I describe the need for the visual plugin. It seems to be related to this question, i.e., the plugin is somehow running before the rendering engine is initialized, but I don't know of any other way other than the visual plugin.