Skip to content

Commit 050ddcb

Browse files
committed
Merge pull request #11 from athackst/nodelet
updated prosilica driver to be a nodelet
2 parents a7be5ab + 84f39b1 commit 050ddcb

File tree

9 files changed

+1202
-1005
lines changed

9 files changed

+1202
-1005
lines changed

README.md

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
prosilica_driver
2+
================
3+
4+
Contains the ROS driver and the SDK for AVT/Prosilica cameras.
5+
6+
This code was originally developed by Willow Garage and has been edited by Allison Thackston
7+
8+
This software is released under a BSD license:
9+
10+
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
11+
12+
Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
13+
Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
14+
Neither the name of the Carnegie Mellon University nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
15+
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
16+

prosilica_camera/CMakeLists.txt

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,10 @@ find_package(catkin REQUIRED COMPONENTS
1515
rosconsole
1616
dynamic_reconfigure
1717
camera_calibration_parsers
18-
polled_camera)
18+
polled_camera
19+
nodelet
20+
nodelet_topic_tools
21+
)
1922

2023
find_package(Boost REQUIRED COMPONENTS thread)
2124

@@ -29,9 +32,14 @@ catkin_package()
2932
add_library(prosilica src/libprosilica/prosilica.cpp)
3033
target_link_libraries(prosilica ${catkin_LIBRARIES})
3134

35+
add_library(prosilica_nodelet src/nodes/prosilica_nodelet.cpp)
36+
target_link_libraries(prosilica_nodelet prosilica ${catkin_LIBRARIES})
37+
class_loader_hide_library_symbols(prosilica_nodelet)
38+
3239
add_executable(prosilica_node src/nodes/prosilica_node.cpp)
3340
target_link_libraries(prosilica_node
34-
prosilica
41+
prosilica
42+
prosilica_nodelet
3543
${Boost_LIBRARIES}
3644
${catkin_LIBRARIES})
3745
add_dependencies(prosilica_node
@@ -58,13 +66,13 @@ target_link_libraries(set_inhibition prosilica ${catkin_LIBRARIES})
5866
install(TARGETS prosilica_node write_memory read_memory set_ip set_inhibition
5967
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
6068

61-
install(TARGETS prosilica
69+
install(TARGETS prosilica prosilica_nodelet
6270
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
6371
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
6472
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
6573

6674
install(DIRECTORY launch
6775
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
6876

69-
install(FILES prosilica.launch streaming.launch
77+
install(FILES prosilica.launch streaming.launch plugins/nodelet_plugins.xml
7078
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

prosilica_camera/cfg/ProsilicaCamera.cfg

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,14 +8,17 @@ from dynamic_reconfigure.parameter_generator_catkin import *
88
gen = ParameterGenerator()
99

1010
mode_enum = gen.enum( [ gen.const("StreamingMode", str_t, "streaming", "Run at maximum frame rate"),
11+
gen.const("SoftwareMode", str_t, "software", "Trigger from software"),
1112
gen.const("PolledMode", str_t, "polled", "Capture frame in response to service call"),
13+
gen.const("TriggerMode", str_t, "triggered", "Capture frame in response to trigger topic"),
1214
gen.const("FixedRateMode", str_t, "fixedrate", "Fixed Rate mode"),
1315
gen.const("External1Mode", str_t, "syncin1", "External trigger on SyncIn1 line"),
1416
gen.const("External2Mode", str_t, "syncin2", "External trigger on SyncIn2 line") ],
1517
"Enum to set the trigger mode")
1618

1719
# Name Type Reconfiguration level Description Default Min Max
18-
gen.add("trigger_mode", str_t, SensorLevels.RECONFIGURE_STOP, "Camera trigger mode", "streaming", edit_method = mode_enum)
20+
gen.add("trigger_mode", str_t, SensorLevels.RECONFIGURE_STOP, "Camera trigger mode", "fixedrate", edit_method = mode_enum)
21+
gen.add("trig_rate", double_t, SensorLevels.RECONFIGURE_STOP, "Sets the expected triggering rate in externally triggered mode.", 1, 1, 100)
1922
gen.add("auto_exposure", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the camera exposure duration to automatic. Causes the `~exposure` setting to be ignored.", True)
2023
gen.add("exposure", double_t, SensorLevels.RECONFIGURE_RUNNING, "Camera exposure time in seconds.", 0.025, 0.000025, 60.0)
2124
gen.add("auto_gain", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the analog gain to automatic. Causes the `~gain` setting to be ignored.", True)
@@ -30,8 +33,7 @@ gen.add("y_offset", int_t, SensorLevels.RECONFIGURE_RUNNING, "Y o
3033
gen.add("width", int_t, SensorLevels.RECONFIGURE_RUNNING, "Width of the region of interest (0 for automatic).", 0, 0, 2448)
3134
gen.add("height", int_t, SensorLevels.RECONFIGURE_RUNNING, "Height of the region of interest (0 for automatic).", 0, 0, 2050)
3235
gen.add("frame_id", str_t, SensorLevels.RECONFIGURE_RUNNING, "The optical camera TF frame set in message headers.", "")
33-
gen.add("trig_timestamp_topic", str_t, SensorLevels.RECONFIGURE_STOP, "Sets the topic from which an externally trigged camera receives its trigger timestamps.", "")
34-
gen.add("trig_rate", double_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the expected triggering rate in externally triggered mode.", 15, 1, 100)
36+
gen.add("trig_timestamp_topic", str_t, SensorLevels.RECONFIGURE_STOP, "Sets the topic from which an externally trigged camera receives its trigger timestamps.", "trigger")
3537
gen.add("auto_adjust_stream_bytes_per_second", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Whether the node should automatically adjust the data rate. Causes `~stream_bytes_per_second` to be ignored.", True)
3638
gen.add("stream_bytes_per_second", int_t, SensorLevels.RECONFIGURE_RUNNING, "Limits the data rate of the camera.", 45000000, 1, 115000000)
3739
gen.add("exposure_auto_max", double_t, SensorLevels.RECONFIGURE_RUNNING, "The max exposure time in auto exposure mode, in seconds.", 0.5, 0.000025, 60.0)
@@ -40,3 +42,4 @@ gen.add("gain_auto_max", int_t, SensorLevels.RECONFIGURE_RUNNING, "The
4042
gen.add("gain_auto_target", int_t, SensorLevels.RECONFIGURE_RUNNING, "The auto gain target mean value as a percentage, from 0=black to 100=white.", 50, 0, 100)
4143

4244
exit(gen.generate(PACKAGE, "prosilica_driver", "ProsilicaCamera"))
45+

prosilica_camera/include/prosilica/prosilica.h

Lines changed: 37 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737

3838
#include <stdexcept>
3939
#include <string>
40+
#include <sstream>
4041
#include <boost/function.hpp>
4142
#include <boost/thread.hpp>
4243

@@ -48,6 +49,15 @@
4849
#undef _LINUX
4950
#undef _x86
5051

52+
53+
template <class T>
54+
inline std::string to_string (const T& t)
55+
{
56+
std::stringstream ss;
57+
ss << t;
58+
return ss.str();
59+
}
60+
5161
namespace prosilica {
5262

5363
struct ProsilicaException : public std::runtime_error
@@ -58,11 +68,21 @@ struct ProsilicaException : public std::runtime_error
5868
: std::runtime_error(msg), error_code(code)
5969
{}
6070
};
71+
struct CameraInfo
72+
{
73+
std::string serial;
74+
std::string name;
75+
std::string guid;
76+
std::string ip_address;
77+
bool access;
78+
};
6179

62-
void init(); // initializes API
63-
void fini(); // releases internal resources
64-
size_t numCameras(); // number of cameras found
65-
uint64_t getGuid(size_t i); // camera ids
80+
void init(); // initializes API
81+
void fini(); // releases internal resources
82+
size_t numCameras(); // number of cameras found
83+
uint64_t getGuid(size_t i); // camera ids
84+
std::vector<CameraInfo> listCameras(); // get list of cameras available
85+
std::string getIPAddress(uint64_t guid); //get ip address data from guid
6686

6787
/// According to FrameStartTriggerMode Enum - AVT GigE Camera and Driver Attributes
6888
/// Firmware 1.38 April 7,2010
@@ -104,10 +124,14 @@ class Camera
104124
//! Must be used before calling start() in a non-triggered mode.
105125
void setFrameCallback(boost::function<void (tPvFrame*)> callback);
106126
void setFrameRate(tPvFloat32 frame_rate);
127+
128+
void setKillCallback(boost::function<void (unsigned long)> callback);
107129
//! Start capture.
108-
void start(FrameStartTriggerMode = Freerun, AcquisitionMode = Continuous);
130+
void start(FrameStartTriggerMode = Freerun, tPvFloat32 frame_rate = 30, AcquisitionMode = Continuous);
109131
//! Stop capture.
110132
void stop();
133+
//! remove callback
134+
void removeEvents();
111135
//! Capture a single frame from the camera. Must be called after
112136
//! start(Software Triggered).
113137
tPvFrame* grab(unsigned long timeout_ms = PVINFINITE);
@@ -159,13 +183,21 @@ class Camera
159183
FrameStartTriggerMode FSTmode_;
160184
AcquisitionMode Amode_;
161185
boost::function<void (tPvFrame*)> userCallback_;
186+
boost::function<void (unsigned long UniqueId)> killCallback_;
162187
boost::mutex frameMutex_;
188+
boost::mutex aliveMutex_;
189+
size_t bufferIndex_;
163190

164191
void setup();
165192

166193
static void frameDone(tPvFrame* frame);
194+
static void kill(void* Context,
195+
tPvInterface Interface,
196+
tPvLinkEvent Event,
197+
unsigned long UniqueId);
167198
};
168199

169200
} // namespace prosilica
170201

171202
#endif
203+

prosilica_camera/package.xml

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
<!-- <url type="bugtracker"></url> -->
1111

1212
<author>Maintained by William Woodall - [email protected]</author>
13+
<author>Contributions by Allison Thackston - [email protected]</author>
1314

1415
<buildtool_depend>catkin</buildtool_depend>
1516

@@ -26,6 +27,8 @@
2627
<build_depend>camera_calibration_parsers</build_depend>
2728
<build_depend>polled_camera</build_depend>
2829
<build_depend>rosconsole</build_depend>
30+
<build_depend>nodelet</build_depend>
31+
<build_depend>nodelet_topic_tools</build_depend>
2932

3033
<run_depend>prosilica_gige_sdk</run_depend>
3134
<run_depend>roscpp</run_depend>
@@ -39,5 +42,11 @@
3942
<run_depend>dynamic_reconfigure</run_depend>
4043
<run_depend>camera_calibration_parsers</run_depend>
4144
<run_depend>polled_camera</run_depend>
45+
<run_depend>nodelet</run_depend>
46+
<run_depend>nodelet_topic_tools</run_depend>
47+
48+
<export>
49+
<nodelet plugin="${prefix}/plugins/nodelet_plugins.xml" />
50+
</export>
4251

4352
</package>
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
<library path="lib/libprosilica_nodelet">
2+
<class name="prosilica_camera/driver" type="prosilica_camera::ProsilicaNodelet" base_class_type="nodelet::Nodelet">
3+
<description>
4+
A nodelet version of the prosilica camera driver
5+
</description>
6+
</class>
7+
</library>
8+

0 commit comments

Comments
 (0)