Closed MacIElson closed 6 years ago
When I say "Using FlyCap2 I am able to adjust the resolution/mode without issue" I mean I can change the resolution via the custom video modes tab.
Point Grey no longer supports standard video modes (support person told me so). How can I set the pointgrey_camera_driver to custom video mode?
Hi @MaciCrowell, thanks for the ticket and for providing the feedback directly from Pt. Grey. I don't have the bandwidth to debug this myself, but I would be happy to test and review a pull request.
I'm seeing a similar issue, when launching bumblebee.launch I get the following error:
Reconfigure Callback failed with error: PointGreyCamera::setFormat7 Error validating Format 7 settings | FlyCapture2::ErrorType 22Error setting Format 7 information.
However, the topics seem to be publishing data regardless of the error.
I'm seeing this on a Bumblebee2; it's preventing the camera from initializing properly. I see the issue on master, 0.12.0, and 0.11.0.
0.10.0 works correctly, with 035b2e9274de2cd01a7bdf8e25f5036869b46b6e cherry-picked in.
Update: The master branch works correctly with 710221e77c52274efd2557d8c894400a3305c157 reverted. Now investigating further. @mmunaro, any idea what's going on here?
Okay, this modification to the launch file fixes Bumblebee2: https://github.com/ros-drivers/pointgrey_camera_driver/compare/fix-bumblebee
I guess the question is, since you're seeing this with a non-Bumblebee, should we be changing the default value of the configuration parameter to raw16
rather than just overriding it in bumblebee.launch
?
@mmunaro, @chadrockey, thoughts on this?
Thanks for that, I'm a beginner with the BB2 and ROS and it did solve the problem on a ROS Indigo fresh install.
@MaciCrowell Hi buddy, have you solved your problem? In fact, I want to get 640x480 resolution, but I cannot do this by rqt_reconfigure or anything?
I have a same problem with the newest ros driver on a pointgrey camera. What is the final solution? It seems the above ones don't work.
Here is the camera information.
[0]Serial: 14340548, Model: Grasshopper3 GS3-U3-41C6C, Vendor: Point Grey Research, Sensor: CMOSIS CMV4000 (1" 2048x2048 CMOS), Resolution: 2048x2048, Color: true, Firmware Version: 2.7.3.0
Error when launch camera driver:
[ERROR] [1467226298.463175814]: Reconfigure Callback failed with error: PointGreyCamera::setVideoMode Could not set video mode | FlyCapture2::ErrorType 7The given video mode and frame rate is not supported by this camera.
The Flycapture library used is flycapture2-2.9.3.43-amd64 downloaded from PointGrey website.
Launch File:
<launch>
<arg name="camera_serial" default="14340548" />
<arg name="calibrated" default="0" />
<group ns="camera">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" />
<node pkg="nodelet" type="nodelet" name="camera_nodelet"
args="load pointgrey_camera_driver/PointGreyCameraNodelet camera_nodelet_manager" >
<param name="frame_id" value="camera" />
<param name="serial" value="$(arg camera_serial)" />
<param name="video_mode" value="640x480_mono8" />
<!-- When unspecified, the driver will use the default framerate as given by the
camera itself. Use this parameter to override that value for cameras capable of
other framerates. -->
<!--param name="frame_rate" value="15" /-->
<!-- Use the camera_calibration package to create this file -->
<param name="camera_info_url" if="$(arg calibrated)"
value="file://$(env HOME)/.ros/camera_info/$(arg camera_serial).yaml" />
</node>
<node pkg="nodelet" type="nodelet" name="image_proc_debayer"
args="load image_proc/debayer camera_nodelet_manager">
</node>
</group>
<node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
<remap from="image" to="/camera/image_raw"/>
<param name="autosize" value="true" />
</node>
<node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" />
</launch>
Solution for my case
sudo sh -c 'echo 1000 > /sys/module/usbcore/parameters/usbfs_memory_mb'
Whenever I try to set the video mode I get the following error:
[ERROR] [1427498291.273185190]: Reconfigure Callback failed with error: PointGreyCamera::setVideoMode Could not set video mode | FlyCapture2::ErrorType 7The given video mode and frame rate is not supported by this camera.
I've tried setting it in both via command line and the launch file. This is the line in the launch file:
param name="video_mode" value="Format0_Mode5"
I'm using a point grey grasshopper3 GS3-U3-23S6C camera. Using FlyCap2 I am able to adjust the resolution/mode without issue.
Any thoughts or help would be appreciated.