File tree 1 file changed +17
-1
lines changed
prosilica_camera/src/nodes
1 file changed +17
-1
lines changed Original file line number Diff line number Diff line change 47
47
#include < sensor_msgs/CameraInfo.h>
48
48
#include < sensor_msgs/fill_image.h>
49
49
#include < sensor_msgs/SetCameraInfo.h>
50
-
51
50
#include < boost/thread.hpp>
51
+ #include < netdb.h>
52
+ #include < arpa/inet.h>
52
53
53
54
#include < prosilica_camera/ProsilicaCameraConfig.h>
54
55
#include " prosilica/prosilica.h"
@@ -253,6 +254,21 @@ class ProsilicaNodelet : public nodelet::Nodelet
253
254
{
254
255
state_info_ = " Trying to load camera with ipaddress: " + ip_address_;
255
256
NODELET_INFO (" %s" , state_info_.c_str ());
257
+ /* Resolve hostname */
258
+ struct hostent *he;
259
+ if ((he = gethostbyname (ip_address_.c_str ())) != NULL )
260
+ {
261
+ struct in_addr **addr_list
262
+ = (struct in_addr **)he->h_addr_list ;
263
+ for (int i = 0 ; addr_list[i] != NULL ; i++)
264
+ {
265
+ // Return the first one;
266
+ ip_address_ = std::string (inet_ntoa (*addr_list[i]));
267
+ NODELET_INFO (" ip resolved as %s" , ip_address_.c_str ());
268
+ break ;
269
+ }
270
+ }
271
+
256
272
camera_ = boost::make_shared<prosilica::Camera>(ip_address_.c_str ());
257
273
guid_ = camera_->guid ();
258
274
hw_id_ = boost::lexical_cast<std::string>(guid_);
You can’t perform that action at this time.
0 commit comments