arv_camera_new() doesn't open the camera when called within a nodelet
Platform Details:
Ubuntu 14.04 LTS Linux Kernel 4.4.0-112-generic
ROS Version: Indigo
ROS Package: camera_aravis
from here - https://github.com/linknum23/camera_aravis
Aravis LIbrary - aravis-0.4.1
from here - http://ftp.acc.umu.se/pub/GNOME/sources/aravis/0.4/ . I have also tried version 0.5.11 with same results.
Cameras used (Same behavior with all cameras and all are GigE cameras):
- IDS GV-527xFA-C
- Allied Vision Mako G-319C
- Allied Vision GT1930C
Each camera is tested separately and is powered through PoE (Power over Ethernet) and the Ethernet packet size has been set to 9000 MTU.
Command to run after compiling the package: rosrun camera_aravis camera_node
The node then detects the camera and can print the device ID and also can access Vendor name and other camera specific parameters with Aravis API's. However, the call to arv_camera_new()
in src/camera_nodelet.cpp returns NULL or doesn't return at all (hangs).
After trying different debugging methods, I narrowed down the issue to Nodelet manager in src/camera_node.cpp.
In the modified camera_node.cpp below, the arv_camera_new()
function can detect the camera and return a camera object.
#include <ros/ros.h>
#include <nodelet/loader.h>
#include <camera_aravis/camera_nodelet.h>
int main(int argc, char** argv)
{
ros::init(argc, argv, "camera_node");
//nodelet::Loader manager(true);
//nodelet::M_string remappings;
//nodelet::V_string my_argv;
arv_update_device_list();
printf("Devices: %d\n", arv_get_n_devices());
ArvCamera *pCamera = arv_camera_new(NULL);
if(pCamera){
printf("Device Opened: %s\n",arv_camera_get_vendor_name(pCamera));
}
else{
printf("Device couldn't be opened\n");
}
//manager.load(ros::this_node::getName(), "camera_aravis/CameraNodelet", remappings, my_argv);
ros::spin();
}
As you can see, I have commented out the Nodelet Manager and directly calling the Aravis APIs to access the camera. I also wrote a separate non-ROS C++ program to use Aravis API's and can access the camera without any issues.
Further more, the test scripts provided within aravis library (Ex: tools/arvcameratest.c) work fine and can connect and stream data from the cameras.
So, the symptoms can be bolied down to arv_camera_new()
and arv_open_device()
(may be other similar APIs which I haven't tested) can find the camera directly in the node, but not when called within the nodelet. Another thing to note is that, other API's such as arv_get_n_devices()
, arv_get_device_id()
work fine in both node and nodelet.
I have reproduced the issue with two machines with same platform and software versions mentioned above. Note that the code is directly taken from the camera_aravis
github repo mentioned above and modifications are only done to camera_node.cpp as shown above while debugging.
What might be going wrong? Anyone experienced similar issues with this package? Any help in debugging would be greatly appreciated.
EDIT:
After digging deeper into Aravis library(0.4.1) and glib (v2.0), I found out that the function g_regex_split
behaves differently for a node and nodelet implementation. Below is the function call to g_regex_split
in arvgvdevice.c
tokens = g_regex_split (arv_gv_device_get_url_regex (), filename, 0);
For the filename string - local:GV-527xFA-C_1_3_120.zip;70000000;3fd0
, the tokens
after ...
I was going to suggest making an issue on the main repo but it looks like that one isn't getting maintained, and there are many many forks with different variations- some of those may or may not have your issue. Maybe you can get in contact with one of the fork authors that has made recent changes.
I have reached out to the fork author. Waiting for their response.