Skip to content

Commit e00a239

Browse files
garaemoneisoku9618
authored andcommitted
Resolve hostname as IP
1 parent 050ddcb commit e00a239

File tree

1 file changed

+17
-1
lines changed

1 file changed

+17
-1
lines changed

prosilica_camera/src/nodes/prosilica_nodelet.cpp

+17-1
Original file line numberDiff line numberDiff line change
@@ -47,8 +47,9 @@
4747
#include <sensor_msgs/CameraInfo.h>
4848
#include <sensor_msgs/fill_image.h>
4949
#include <sensor_msgs/SetCameraInfo.h>
50-
5150
#include <boost/thread.hpp>
51+
#include <netdb.h>
52+
#include <arpa/inet.h>
5253

5354
#include <prosilica_camera/ProsilicaCameraConfig.h>
5455
#include "prosilica/prosilica.h"
@@ -253,6 +254,21 @@ class ProsilicaNodelet : public nodelet::Nodelet
253254
{
254255
state_info_ = "Trying to load camera with ipaddress: " + ip_address_;
255256
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+
256272
camera_ = boost::make_shared<prosilica::Camera>(ip_address_.c_str());
257273
guid_ = camera_->guid();
258274
hw_id_ = boost::lexical_cast<std::string>(guid_);

0 commit comments

Comments
 (0)