diff --git a/package.xml b/package.xml
index 72e0145..0665055 100644
--- a/package.xml
+++ b/package.xml
@@ -12,6 +12,7 @@
gazebo_ros
roscpp
camera_info_manager
+ libopencv-dev
depth_image_proc
diff --git a/src/RealSensePlugin.cpp b/src/RealSensePlugin.cpp
index 29fc2cd..af9f3ab 100644
--- a/src/RealSensePlugin.cpp
+++ b/src/RealSensePlugin.cpp
@@ -66,18 +66,23 @@ void RealSensePlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
// Sensors Manager
sensors::SensorManager *smanager = sensors::SensorManager::Instance();
- // Get Cameras Renderers
+ std::vector DEPTH_CAMERA_FULL_NAME = this->rsModel->SensorScopedName(DEPTH_CAMERA_NAME);
+ std::vector IRED1_CAMERA_FULL_NAME = this->rsModel->SensorScopedName(IRED1_CAMERA_NAME);
+ std::vector IRED2_CAMERA_FULL_NAME = this->rsModel->SensorScopedName(IRED2_CAMERA_NAME);
+ std::vector COLOR_CAMERA_FULL_NAME = this->rsModel->SensorScopedName(COLOR_CAMERA_NAME);
+
+ // Get Cameras Renderers
this->depthCam =
std::dynamic_pointer_cast(
- smanager->GetSensor(DEPTH_CAMERA_NAME))->DepthCamera();
+ smanager->GetSensor(DEPTH_CAMERA_FULL_NAME.front()))->DepthCamera();
this->ired1Cam = std::dynamic_pointer_cast(
- smanager->GetSensor(IRED1_CAMERA_NAME))
+ smanager->GetSensor(IRED1_CAMERA_FULL_NAME.front()))
->Camera();
this->ired2Cam = std::dynamic_pointer_cast(
- smanager->GetSensor(IRED2_CAMERA_NAME))
+ smanager->GetSensor(IRED2_CAMERA_FULL_NAME.front()))
->Camera();
this->colorCam = std::dynamic_pointer_cast(
- smanager->GetSensor(COLOR_CAMERA_NAME))
+ smanager->GetSensor(COLOR_CAMERA_FULL_NAME.front()))
->Camera();
// Check if camera renderers have been found successfuly
@@ -129,11 +134,11 @@ void RealSensePlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
this->depthPub = this->transportNode->Advertise(
rsTopicRoot + DEPTH_CAMERA_TOPIC, 1, DEPTH_PUB_FREQ_HZ);
this->ired1Pub = this->transportNode->Advertise(
- rsTopicRoot + IRED1_CAMERA_TOPIC, 1, DEPTH_PUB_FREQ_HZ);
+ rsTopicRoot + IRED1_CAMERA_TOPIC, 1, IRED1_PUB_FREQ_HZ);
this->ired2Pub = this->transportNode->Advertise(
- rsTopicRoot + IRED2_CAMERA_TOPIC, 1, DEPTH_PUB_FREQ_HZ);
+ rsTopicRoot + IRED2_CAMERA_TOPIC, 1, IRED2_PUB_FREQ_HZ);
this->colorPub = this->transportNode->Advertise(
- rsTopicRoot + COLOR_CAMERA_TOPIC, 1, DEPTH_PUB_FREQ_HZ);
+ rsTopicRoot + COLOR_CAMERA_TOPIC, 1, COLOR_PUB_FREQ_HZ);
// Listen to depth camera new frame event
this->newDepthFrameConn = this->depthCam->ConnectNewDepthFrame(