Skip to content

Commit c314035

Browse files
garaemoneisoku9618
authored andcommitted
Add ~hostname parameter to resolve hostname as IP
1 parent 050ddcb commit c314035

File tree

1 file changed

+32
-1
lines changed

1 file changed

+32
-1
lines changed

prosilica_camera/src/nodes/prosilica_nodelet.cpp

+32-1
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,8 @@
4949
#include <sensor_msgs/SetCameraInfo.h>
5050

5151
#include <boost/thread.hpp>
52+
#include <netdb.h>
53+
#include <arpa/inet.h>
5254

5355
#include <prosilica_camera/ProsilicaCameraConfig.h>
5456
#include "prosilica/prosilica.h"
@@ -123,6 +125,7 @@ class ProsilicaNodelet : public nodelet::Nodelet
123125
unsigned long guid_;
124126
std::string hw_id_;
125127
std::string ip_address_;
128+
std::string hostname_;
126129
double open_camera_retry_period_;
127130
std::string trig_timestamp_topic_;
128131
ros::Time trig_time_;
@@ -204,6 +207,8 @@ class ProsilicaNodelet : public nodelet::Nodelet
204207

205208
pn.param<std::string>("ip_address", ip_address_, "");
206209
NODELET_INFO("Loaded ip address: %s", ip_address_.c_str());
210+
pn.param<std::string>("hostname", hostname_, "");
211+
NODELET_INFO("Loaded ip address: %s", hostname_.c_str());
207212

208213
pn.param<double>("open_camera_retry_period", open_camera_retry_period_, 3.);
209214
NODELET_INFO("Retry period: %f", open_camera_retry_period_);
@@ -260,6 +265,29 @@ class ProsilicaNodelet : public nodelet::Nodelet
260265

261266
NODELET_INFO("Started Prosilica camera with guid \"%d\"", (int)camera_->guid());
262267
}
268+
else if(!hostname_.empty())
269+
{
270+
state_info_ = "Trying to load camera with hostname: " + hostname_;
271+
NODELET_INFO("%s", state_info_.c_str());
272+
/* Resolve hostname */
273+
struct hostent *he;
274+
if ((he = gethostbyname(hostname_.c_str())) != NULL)
275+
{
276+
std::string resolved_hostname = std::string(inet_ntoa(*(struct in_addr*)(he->h_addr)));
277+
NODELET_INFO("hostname resolved as %s", resolved_hostname.c_str());
278+
camera_ = boost::make_shared<prosilica::Camera>(resolved_hostname.c_str());
279+
guid_ = camera_->guid();
280+
hw_id_ = boost::lexical_cast<std::string>(guid_);
281+
updater.setHardwareIDf("%d", guid_);
282+
283+
NODELET_INFO("Started Prosilica camera with guid \"%d\"", (int)camera_->guid());
284+
}
285+
else
286+
{
287+
NODELET_FATAL("Failed to resolve hostname: %s", hostname_.c_str());
288+
throw std::runtime_error("Failed to resolve hostname");
289+
}
290+
}
263291
else
264292
{
265293
updater.setHardwareID("unknown");
@@ -296,7 +324,10 @@ class ProsilicaNodelet : public nodelet::Nodelet
296324
{
297325
err << "Unable to open prosilica camera with ip address " << ip_address_ <<": "<<e.what();
298326
}
299-
327+
else if (hostname_ != "")
328+
{
329+
err << "Unable to open prosilica camera with hostname " << hostname_ <<": "<<e.what();
330+
}
300331
state_info_ = err.str();
301332
NODELET_WARN("%s", state_info_.c_str());
302333
if(prosilica::numCameras() > 0)

0 commit comments

Comments
 (0)