|
49 | 49 | #include <sensor_msgs/SetCameraInfo.h>
|
50 | 50 |
|
51 | 51 | #include <boost/thread.hpp>
|
| 52 | +#include <netdb.h> |
| 53 | +#include <arpa/inet.h> |
52 | 54 |
|
53 | 55 | #include <prosilica_camera/ProsilicaCameraConfig.h>
|
54 | 56 | #include "prosilica/prosilica.h"
|
@@ -123,6 +125,7 @@ class ProsilicaNodelet : public nodelet::Nodelet
|
123 | 125 | unsigned long guid_;
|
124 | 126 | std::string hw_id_;
|
125 | 127 | std::string ip_address_;
|
| 128 | + std::string hostname_; |
126 | 129 | double open_camera_retry_period_;
|
127 | 130 | std::string trig_timestamp_topic_;
|
128 | 131 | ros::Time trig_time_;
|
@@ -204,6 +207,8 @@ class ProsilicaNodelet : public nodelet::Nodelet
|
204 | 207 |
|
205 | 208 | pn.param<std::string>("ip_address", ip_address_, "");
|
206 | 209 | 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()); |
207 | 212 |
|
208 | 213 | pn.param<double>("open_camera_retry_period", open_camera_retry_period_, 3.);
|
209 | 214 | NODELET_INFO("Retry period: %f", open_camera_retry_period_);
|
@@ -260,6 +265,29 @@ class ProsilicaNodelet : public nodelet::Nodelet
|
260 | 265 |
|
261 | 266 | NODELET_INFO("Started Prosilica camera with guid \"%d\"", (int)camera_->guid());
|
262 | 267 | }
|
| 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 | + } |
263 | 291 | else
|
264 | 292 | {
|
265 | 293 | updater.setHardwareID("unknown");
|
@@ -296,7 +324,10 @@ class ProsilicaNodelet : public nodelet::Nodelet
|
296 | 324 | {
|
297 | 325 | err << "Unable to open prosilica camera with ip address " << ip_address_ <<": "<<e.what();
|
298 | 326 | }
|
299 |
| - |
| 327 | + else if (hostname_ != "") |
| 328 | + { |
| 329 | + err << "Unable to open prosilica camera with hostname " << hostname_ <<": "<<e.what(); |
| 330 | + } |
300 | 331 | state_info_ = err.str();
|
301 | 332 | NODELET_WARN("%s", state_info_.c_str());
|
302 | 333 | if(prosilica::numCameras() > 0)
|
|
0 commit comments