File tree Expand file tree Collapse file tree 1 file changed +10
-0
lines changed
prosilica_camera/src/nodes Expand file tree Collapse file tree 1 file changed +10
-0
lines changed Original file line number Diff line number Diff line change 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"
@@ -253,6 +255,14 @@ class ProsilicaNodelet : public nodelet::Nodelet
253255 {
254256 state_info_ = " Trying to load camera with ipaddress: " + ip_address_;
255257 NODELET_INFO (" %s" , state_info_.c_str ());
258+ /* Resolve hostname */
259+ struct hostent *he;
260+ if ((he = gethostbyname (ip_address_.c_str ())) != NULL )
261+ {
262+ ip_address_ = std::string (inet_ntoa (*(struct in_addr *)(he->h_addr )));
263+ NODELET_INFO (" ip resolved as %s" , ip_address_.c_str ());
264+ }
265+
256266 camera_ = boost::make_shared<prosilica::Camera>(ip_address_.c_str ());
257267 guid_ = camera_->guid ();
258268 hw_id_ = boost::lexical_cast<std::string>(guid_);
You can’t perform that action at this time.
0 commit comments