Skip to content

Commit

Permalink
Migration to Gz Ignition
Browse files Browse the repository at this point in the history
  • Loading branch information
KiselevIlia committed Sep 14, 2023
1 parent 045778e commit 6a184eb
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 7 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -417,7 +417,7 @@ set(plugins
)

foreach(plugin ${plugins})
target_link_libraries(${plugin} ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${TinyXML_LIBRARIES})
target_link_libraries(${plugin} ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${TinyXML_LIBRARIES} ignition-gazebo1-ignition-sensors)
endforeach()
target_link_libraries(gazebo_opticalflow_plugin ${OpticalFlow_LIBS})

Expand Down
10 changes: 5 additions & 5 deletions include/gazebo_sensor_plugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,26 +2,26 @@

#include <string>

#include <gazebo/gazebo.hh>
#include <gazebo/sensors/sensors.hh>
#include <ignition/gazebo.hh>
#include <ignition/gazebo/Sensors.hh>

namespace gazebo
{

class CollisionPlugin : public SensorPlugin
class CollisionPlugin : public ignition::gazebo::SensorPlugin
{

public:
CollisionPlugin(){}

virtual ~CollisionPlugin(){}

virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf) override;

private:
std::string GetObjName(std::string const& object);

virtual void OnUpdate();
void OnUpdate() override;
sensors::ContactSensorPtr parentSensor;
event::ConnectionPtr updateConnection;
transport::NodePtr node;
Expand Down
2 changes: 1 addition & 1 deletion src/gazebo_sensor_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include "SensorMessage.pb.h"

using namespace gazebo;
GZ_REGISTER_SENSOR_PLUGIN(CollisionPlugin)
IGNITION_ADD_PLUGIN(CollisionPlugin)

void CollisionPlugin::Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
{
Expand Down

0 comments on commit 6a184eb

Please sign in to comment.