Bluefox2
Build status |
---|
This driver depends on package camera_base
https://github.com/KumarRobotics/bluefox2
Supported hardware
This driver should work with any Matrix-Vision Bluefox usb2.0 MLC cameras (bluefox2).
Finding camera serial number
Run rosrun bluefox2 bluefox2_list_cameras
to list info about all connected cameras.
API Stability
The ROS API of this driver should be considered unstable.
ROS API
Single nodelet
single_nodelet.launch
is a nodelet for a single bluefox2 camera.- Can be included in custom launch files.
Example
example.lauch
is an example of how to includesingle_nodelet.launch
in custom launch files.
Published topics
~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.
Parameters
Common interface
~device
(string
)
The device serial id.
~fps
(double
)
The desired frame rate of the camera.
Normal parameters
~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 mv_<serial>.yaml
.
~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.
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.
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.
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.
Hardware sync
Notice that if you are using two 200w cameras, there's no need to use hardware synchronization because software synchronization is supported.
Using 2 mvBlueFOX-MLC cameras in Master-Slave mode
Single-board version (mvBlueFOX-MLC2xx)
Install mvIMPACT Driver
Run:
./install/install.sh
This will install mvIMPACT_Acquire SDK to /opt
.
wxPropView
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.
FAQs
-
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.13