Skip to content

Commit 3991df7

Browse files
authored
Merge pull request #15 from jnmacdnld/kinetic-devel
Remove driver_base dependency as this package is deprecated
2 parents 050ddcb + 0d0c7ac commit 3991df7

File tree

4 files changed

+5
-8
lines changed

4 files changed

+5
-8
lines changed

prosilica_camera/CMakeLists.txt

-1
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@ find_package(catkin REQUIRED COMPONENTS
1111
diagnostic_updater
1212
image_transport
1313
self_test
14-
driver_base
1514
rosconsole
1615
dynamic_reconfigure
1716
camera_calibration_parsers

prosilica_camera/cfg/ProsilicaCamera.cfg

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
PACKAGE='prosilica_camera'
44

5-
from driver_base.msg import SensorLevels
5+
from dynamic_reconfigure.msg import SensorLevels
66
from dynamic_reconfigure.parameter_generator_catkin import *
77

88
gen = ParameterGenerator()

prosilica_camera/package.xml

-2
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,6 @@
2222
<build_depend>diagnostic_msgs</build_depend>
2323
<build_depend>image_transport</build_depend>
2424
<build_depend>self_test</build_depend>
25-
<build_depend>driver_base</build_depend>
2625
<build_depend>dynamic_reconfigure</build_depend>
2726
<build_depend>camera_calibration_parsers</build_depend>
2827
<build_depend>polled_camera</build_depend>
@@ -38,7 +37,6 @@
3837
<run_depend>diagnostic_msgs</run_depend>
3938
<run_depend>image_transport</run_depend>
4039
<run_depend>self_test</run_depend>
41-
<run_depend>driver_base</run_depend>
4240
<run_depend>dynamic_reconfigure</run_depend>
4341
<run_depend>camera_calibration_parsers</run_depend>
4442
<run_depend>polled_camera</run_depend>

prosilica_camera/src/nodes/prosilica_nodelet.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@
3636
#include <nodelet/nodelet.h>
3737
#include <image_transport/image_transport.h>
3838
#include <dynamic_reconfigure/server.h>
39-
#include <driver_base/SensorLevels.h>
39+
#include <dynamic_reconfigure/SensorLevels.h>
4040
#include <diagnostic_updater/diagnostic_updater.h>
4141
#include <diagnostic_updater/publisher.h>
4242
#include <camera_calibration_parsers/parse_ini.h>
@@ -515,7 +515,7 @@ class ProsilicaNodelet : public nodelet::Nodelet
515515
last_config_.height = req.roi.height;
516516
last_config_.width = req.roi.width;
517517

518-
reconfigureCallback(last_config_, driver_base::SensorLevels::RECONFIGURE_RUNNING);
518+
reconfigureCallback(last_config_, dynamic_reconfigure::SensorLevels::RECONFIGURE_RUNNING);
519519

520520
try
521521
{
@@ -690,7 +690,7 @@ class ProsilicaNodelet : public nodelet::Nodelet
690690
{
691691
NODELET_DEBUG("Reconfigure request received");
692692

693-
if (level >= (uint32_t)driver_base::SensorLevels::RECONFIGURE_STOP)
693+
if (level >= (uint32_t)dynamic_reconfigure::SensorLevels::RECONFIGURE_STOP)
694694
stop();
695695

696696
//! Trigger mode
@@ -865,7 +865,7 @@ class ProsilicaNodelet : public nodelet::Nodelet
865865

866866
//! If exception thrown due to bad settings, it will fail to start camera
867867
//! Reload last good config
868-
if (level >= (uint32_t)driver_base::SensorLevels::RECONFIGURE_STOP)
868+
if (level >= (uint32_t)dynamic_reconfigure::SensorLevels::RECONFIGURE_STOP)
869869
{
870870
try
871871
{

0 commit comments

Comments
 (0)