This driver depends on package camera_base
This driver works with ubuntu 14.04 + ros indigo + gcc 4.8+
This driver follows the google c++ style guide
https://github.com/KumarRobotics/bluefox2
This driver should work with any Matrix-Vision Bluefox usb2.0 MLC cameras (bluefox2).
The ROS API of this driver should be considered unstable.
single_node
is a node for a single bluefox2 camera.
~image_raw
(sensor_msgs/Image)
The unprocessed image data.
~camera_info
(sensor_msgs/CameraInfo)
Contains the camera calibration (if calibrated) and extra data about the camera configuration.
Common interface
~device
(string
)
This will be the same as serial
.
~rate
(double
)
This will be the same as fps
.
Normal parameters
~serial
(string
, default: <device>
)
bluefox2 camera serial number.
~camera_name
(string
, default: mv_<serial>
)
Camera name used by camera_info_manager
for loading calibration file, should be the same as the name in calib_<serial>.yml
.
~camera
(string
, default: <camera_name>
)
Name of the node.
~frame_id
(string
, default: <camera>
)
frame id of the published topics.
~calib_url
(string
)
camera calibration URL.
Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~fps
(double
, default: 20.0
)
frame per second.
~color
(bool
, default: false
)
pixelformat, true
will use RGB888Packed
, false
will use mono8
.
~cbm
(bool
, default: false
)
camera binning mode, true
use BinningHV
, which is horizontal + vertical binning.
~ctm
(int
, default: 1
)
camera trigger mode:
0
- ctm_continuous1
- ctm_on_demand
we recommend using ctm_on_demand for more precise timing control whenever possible. If a device does not support ctm_on_demand, it will be set to ctm_continuous.
~mm
(int
, default: 0
)
mirror mode:
0
- mm_off, no mirroring1
- mm_topdown, resulting image will be flipped around a horizontal axis.2
- mm_leftright, resulting image will be flipped around a vertical axis.3
- resulting image will be both around a horizontal and vertical axis
for now only global mirror operation mode is supported, channel based mirror operation is not.
~aec
(int
, default: 0
)
auto expose control:
0
- aec_off, fixed exposure time1
- aec_on, auto control by driver2
- aec_fix, auto determined by driver and set to a fixed value3
- aec_clamp, auto control by driver, but clamped to expose time set by user inexpose_us
, the pid controller for auto expose controller is tuned by Frank
~expose_us
(int
, default: 5000
)
exposure time in us.
~gain_db
(double
, default: 0.0
)
gain in Db.
~wbp
(int
, default: 0
)
white balance parameter:
-1
- wbp_unavailable0~5
- wbp_tungsten and friends6
~ wbp_user17
- wbp_calibrate, calibrate next frame for white balance
For calibrating white balance, first point the camera at a white board, then select wbp_calibrate
, the mvIMPACT driver will calibrate white balance automatically and save it to wbp_user1
.
~dcfm
(int
, default: 1
)
dark current filter mode:
0
- dcfm_off1
- dcfm_on2
- dcfm_calibrate3
- correction_image
If you are using a color camera, you would want to perform a 'dark current filter calibration` to enhance the quality of acquisition. This is done with the following steps:
- Start the bluefox node, let it run for about 5-6 minutes until the temperature of the sensor reaches a stable value. Then you would see something like this.
- Put the lense cap on so that the image looks like this. You can see that there are some pixels that are not completely dark, this is due to the effect of dark current.
- Select
dcfm_calibrate
from the reconfigure server. The driver will do the dark current calibration and then switch the filter on. You can verify the result by selectingcorrection_image
and you will see this.
- Then you can switch back to
dcfm_on
and your image would look much better then before.
- This calibration process cannot be done automatically since it requires the sensor be running for a few minutes and manually putting the lense cap on.
TODO: turn off offsetautocalibration and set the offset to a proper value during darkcurrentfilter calibration.
Read this article as well.
~hdr
(bool
, default: false
)
Only 200wG camera supports this mode, set hdr
to true
for other cameras will have no effect.
~boost
(bool
, default: false
)
boost mode:
true
- send 2 requests into the request queuefalse
- send only 1 request
This mode is required when high fps desired which allows 200wG to work at 90 fps and 200bG at 24 fps (with ctm = 1
). Using this will result in imprecise time stamp of captured image. Use with caution.
stereo_node
is a node for 2 bluefox2 cameras in stereo configuration.
~left/image_raw
(sensor_msgs/Image)
~right/image_raw
(sensor_msgs/Image)
The unprocessed image data.
~/left/camera_info
(sensor_msgs/CameraInfo)
~/right/camera_info
(sensor_msgs/CameraInfo)
Contains the camera calibration (if calibrated) and extra data about the camera configuration.
Common interface
~rate
(double
)
This will be the same as fps
.
Normal parameters
~left
(string
, default: <left_serial>
)
~right
(string
, default: <right_serial>
)
bluefox2 camera serial number for the left and right camera.
~left_camera_name
(string
, default: mv_<left_serial>
)
~right_camera_name
(string
, default: mv_<right_serial>
)
Camera name used by camera_info_manager
for load calibration file, should be the same as the name in calib_<serial>.yml
.
~left_calib_url
(string
, default: package://bluefox2/calib/calib_<left_serial>.yml
)
~right_calib_url
(string
, default: package://bluefox2/calib/calib_<right_serial>.yml
)
camera calibration URL for the left and right camera.
All the rest parameters are the same with single_node
, changing them will change the corresponding settings in both cameras.
Notice that if you are using two 200w cameras, there's no need to use hardware synchronization because software synchronization is supported. The stereo_node will send two request one after another and the delay could be ignored.
Using 2 mvBlueFOX-MLC cameras in Master-Slave mode
Single-board version (mvBlueFOX-MLC2xx)
Run:
./install/install.sh
This will install mvIMPACT_Acquire SDK to /opt
.
If you install the full matrix vision driver, you will have wxPropView
installed to your system. It's an GUI application that let you inspect all properties of the camera.
-
I have the driver locally in my ros package, but every time I plug in a camera, I need to change the permission.
-
Simple fix:
sudo chmod 777 /dev/bus/usb/xxx/xxx
/dev/bus/usb/xxx/xxx
can be easily identified with the error information ros provids.-
Permanent fix: Adding a rule to
/etc/udev/rules.d
by the following commandsudo cp -f path_to_driver/Scripts/51-mvbf.rules /etc/udev/rules.d/ sudo service udev reload
-
-
Camera acquisition failure after being unplugged and plugged back in If you are using linux kernel 3.13.0, then it's likely that you will encounter this problem. The solution is to install the latest kernel, eg. 3.14.17