Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
I
iri_firewire_camera_driver
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
labrobotica
ros
sensors
mono_cameras
iri_firewire_camera_driver
Commits
354a3c3e
Commit
354a3c3e
authored
6 years ago
by
Fernando Herrero
Browse files
Options
Downloads
Patches
Plain Diff
Update CMakelists with correct cmake plural variables. Add Readme
parent
f61ed90d
No related branches found
No related tags found
1 merge request
!1
Kinetic migration
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
CMakeLists.txt
+13
-12
13 additions, 12 deletions
CMakeLists.txt
README.md
+47
-0
47 additions, 0 deletions
README.md
config/flea_params.yaml
+8
-1
8 additions, 1 deletion
config/flea_params.yaml
launch/nodelet.launch
+34
-0
34 additions, 0 deletions
launch/nodelet.launch
with
102 additions
and
13 deletions
CMakeLists.txt
+
13
−
12
View file @
354a3c3e
...
...
@@ -18,16 +18,16 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs image_transport camera_info_
FIND_PACKAGE
(
iriutils REQUIRED
)
FIND_PACKAGE
(
firewire REQUIRED
)
FIND_LIBRARY
(
raw1394_LIBRAR
Y
FIND_LIBRARY
(
raw1394_LIBRAR
IES
NAMES raw1394
PATHS /usr/lib /usr/local/lib
)
FIND_LIBRARY
(
dc1394_LIBRAR
Y
FIND_LIBRARY
(
dc1394_LIBRAR
IES
NAMES dc1394
PATHS /usr/lib /usr/local/lib
)
IF
(
raw1394_INCLUDE_DIR AND raw1394_LIBRAR
Y
AND dc1394_INCLUDE_DIR AND dc1394_LIBRAR
Y
)
IF
(
raw1394_INCLUDE_DIR
S
AND raw1394_LIBRAR
IES
AND dc1394_INCLUDE_DIR
S
AND dc1394_LIBRAR
IES
)
SET
(
firewire_ready TRUE
)
ENDIF
(
raw1394_INCLUDE_DIR AND raw1394_LIBRAR
Y
AND dc1394_INCLUDE_DIR AND dc1394_LIBRAR
Y
)
ENDIF
(
raw1394_INCLUDE_DIR
S
AND raw1394_LIBRAR
IES
AND dc1394_INCLUDE_DIR
S
AND dc1394_LIBRAR
IES
)
# ********************************************************************
# Add topic, service and action definition here
...
...
@@ -91,8 +91,8 @@ include_directories(include)
include_directories
(
${
catkin_INCLUDE_DIRS
}
)
include_directories
(
${
iriutils_INCLUDE_DIR
}
)
include_directories
(
${
firewire_INCLUDE_DIR
}
)
include_directories
(
${
raw1394_INCLUDE_DIR
}
)
include_directories
(
${
dc1394_INCLUDE_DIR
}
)
include_directories
(
${
raw1394_INCLUDE_DIR
S
}
)
include_directories
(
${
dc1394_INCLUDE_DIR
S
}
)
## Declare a cpp library
add_library
(
${
PROJECT_NAME
}
_nodelet src/firewire_camera_driver_node.cpp src/firewire_camera_driver.cpp
)
...
...
@@ -107,23 +107,24 @@ add_executable(${PROJECT_NAME} src/firewire_camera_driver.cpp src/firewire_camer
target_link_libraries
(
${
PROJECT_NAME
}
${
catkin_LIBRARIES
}
)
target_link_libraries
(
${
PROJECT_NAME
}
${
iriutils_LIBRARY
}
)
target_link_libraries
(
${
PROJECT_NAME
}
${
firewire_LIBRARY
}
)
target_link_libraries
(
${
PROJECT_NAME
}
${
raw1394_LIBRAR
Y
}
)
target_link_libraries
(
${
PROJECT_NAME
}
${
dc1394_LIBRAR
Y
}
)
target_link_libraries
(
${
PROJECT_NAME
}
${
raw1394_LIBRAR
IES
}
)
target_link_libraries
(
${
PROJECT_NAME
}
${
dc1394_LIBRAR
IES
}
)
target_link_libraries
(
${
PROJECT_NAME
}
_nodelet
${
catkin_LIBRARIES
}
)
target_link_libraries
(
${
PROJECT_NAME
}
_nodelet
${
iriutils_LIBRARY
}
)
target_link_libraries
(
${
PROJECT_NAME
}
_nodelet
${
firewire_LIBRARY
}
)
target_link_libraries
(
${
PROJECT_NAME
}
_nodelet
${
raw1394_LIBRAR
Y
}
)
target_link_libraries
(
${
PROJECT_NAME
}
_nodelet
${
dc1394_LIBRAR
Y
}
)
target_link_libraries
(
${
PROJECT_NAME
}
_nodelet
${
raw1394_LIBRAR
IES
}
)
target_link_libraries
(
${
PROJECT_NAME
}
_nodelet
${
dc1394_LIBRAR
IES
}
)
# ********************************************************************
# Add message headers dependencies
# ********************************************************************
# add_dependencies(${PROJECT_NAME} <msg_package_name>_generate_messages_cpp)
add_dependencies
(
${
PROJECT_NAME
}
_gencfg iri_base_driver_generate_messages
)
add_dependencies
(
${
PROJECT_NAME
}
_gencfg
iri_base_driver_generate_messages
)
# ********************************************************************
# Add dynamic reconfigure dependencies
# ********************************************************************
add_dependencies
(
${
PROJECT_NAME
}
${${
PROJECT_NAME
}
_EXPORTED_TARGETS
}
)
add_dependencies
(
${
PROJECT_NAME
}
${${
PROJECT_NAME
}
_EXPORTED_TARGETS
}
)
add_dependencies
(
${
PROJECT_NAME
}
_nodelet
${${
PROJECT_NAME
}
_EXPORTED_TARGETS
}
)
## Specify libraries to link a library or executable target against
# target_link_libraries(foo_node
...
...
This diff is collapsed.
Click to expand it.
README.md
0 → 100644
+
47
−
0
View file @
354a3c3e
# Description
The iri_firewire_camera_driver ROS package is a wrapper of the firewire_camera C++ driver library.
# Dependencies
This node has the following dependencies:
*
[
firewire_camera
](
https://gitlab.iri.upc.edu/labrobotica/drivers/firewire_camera
)
*
[
iri_base_driver
](
https://gitlab.iri.upc.edu/labrobotica/ros/iri_core/iri_base_driver
)
:
# Install
This package, as well as all IRI dependencies, can be installed by cloning the
repository inside the active workspace:
```
roscd
cd ../src
git clone https://gitlab.iri.upc.edu/labrobotica/ros/platforms/segway/iri_segway_rmp200_driver.git
```
However, this package is normally used as part of a wider installation (i.e. a
robot, an experiment or a demosntration) which will normally include a complete
rosinstall file to be used with the
[
wstool
](
http://wiki.ros.org/wstool
)
tool.
# How to use it
<!--
The
*node.launch*
launch file is intended to be included in any launch file
that needs the node. It has the following arguments:
*
name: (default: robot) namespace of the node
*
config_file: (default: $(find iri_segway_rmp200_driver)/config/params.yaml) a configuration file with all the supported parameters.
A default YAML configuration file is provided in the config folder,
but each application can define a new file with the desired parameters and pass it to this launch file.
*
output: (default: log) the desired output for the node. Possible values for this parameter are log and screen.
*
launch_prefix: (default: none)
To remap the topics and services of the driver, use a global remap command.
-->
\ No newline at end of file
This diff is collapsed.
Click to expand it.
config/flea_params.yaml
+
8
−
1
View file @
354a3c3e
...
...
@@ -2,6 +2,13 @@ tf_prefix: "robot"
frame_id
:
"
camera_frame"
Camera_node
:
0
Camera_serial
:
"
"
#known serials
#flea: 00b09d0100a96262
#flea2: 00b09d01006cf72a
#bumblebee dabo: 0814438300001f9c
#bumblebee tibi:
ISO_speed
:
400
Image_width
:
1024
Image_height
:
768
...
...
@@ -18,4 +25,4 @@ Shutter_mode: 0 # 0=Auto, 1=Manual
Shutter_value
:
28
Gain_enabled
:
true
Gain_mode
:
0
# 0=Auto, 1=Manual
Gain_value
:
48
Gain_value
:
48
\ No newline at end of file
This diff is collapsed.
Click to expand it.
launch/nodelet.launch
0 → 100644
+
34
−
0
View file @
354a3c3e
<?xml version="1.0"?>
<!-- -->
<launch>
<arg
name=
"name"
default=
"robot"
/>
<arg
name=
"config_file"
default=
"$(find iri_firewire_camera_driver)/config/params.yaml"
/>
<arg
name=
"output"
default=
"log"
/>
<arg
name=
"launch_prefix"
default=
""
/>
<group
ns=
"$(arg name)"
>
<node
pkg =
"nodelet"
type=
"nodelet"
name=
"standalone_nodelet"
args=
"manager"
output=
"$(arg output)"
launch-prefix=
"$(arg launch_prefix)"
>
<node
pkg=
"nodelet"
type=
"nodelet"
name=
"iri_firewire_camera_driver_nodelet"
args=
"load iri_firewire_camera_driver/FirewireCameraDriverNodelet standalone_nodelet"
output=
"$(arg output)"
launch-prefix=
"$(arg launch_prefix)"
>
<rosparam
file=
"$(arg config_file)"
command=
"load"
/>
</node>
</group>
</launch>
<!-- TODO remaps image_raw, camera_info-->
<!-- TODO params nodelet? -->
<!-- TODO test with image_proc/crop_decimate, image_proc/rectify
\ No newline at end of file
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment