ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Couldn't find an AF_INET address of []

asked 2018-05-01 00:24:04 -0500

reverse3D gravatar image

updated 2018-05-01 03:12:59 -0500

gvdhoorn gravatar image

I have written a ROS node to subscribe to the topics from a rosbag

/sensors/velodyne_points /sensors/camera/image_color /sensors/camera/camera_info

Some excerpts from the code below:

// ROS includes
#include <ros/ros.h>
#include <ros/console.h>
...

// OpenCV includes
...

// Include pcl
...

// Include PointCloud2 ROS message
...

static const std::string OPENCV_WINDOW = "Image window";
const tf::TransformListener tf_listener_;
image_geometry::PinholeCameraModel cam_model_;
tf::StampedTransform transform;
std::vector <tf::Vector3> objectPoints;
tf::Vector3 pt_cv;
std::vector <cv::Point3d> pt_transformed;

void processCallback(const sensor_msgs::ImageConstPtr& image_msg,
    const sensor_msgs::CameraInfoConstPtr& info_msg,
    const sensor_msgs::PointCloud2ConstPtr& pointCloudMsg)
{
    ...
}
int main(int argc, char** argv) 
{
ros::init(argc, argv, "lidar_calibration");

ros::NodeHandle nh;
// ROS_INFO("Starting LiDAR node");

message_filters::Subscriber<sensor_msgs::Image> image_sub(nh, "image", 1);
message_filters::Subscriber<sensor_msgs::CameraInfo> info_sub(nh, "camera_info", 1);
message_filters::Subscriber<sensor_msgs::PointCloud2> lidar_sub(nh, "velodyne_points", 1);
message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> sync(image_sub, info_sub, lidar_sub, 10);
sync.registerCallback(boost::bind(&processCallback, _1, _2, _3));

ros::spin();
// cv::destroyWindow(OPENCV_WINDOW);

return 0;

}

And my ROS variables are:

ROS_ROOT=/opt/ros/kinetic/share/ros
ROS_PACKAGE_PATH=/opt/ros/kinetic/share
ROS_MASTER_URI=http://localhost:11311
ROS_VERSION=1
ROS_MAVEN_DEPLOYMENT_REPOSITORY=/opt/ros/kinetic/share/maven
ROS_MAVEN_PATH=/opt/ros/kinetic/share/maven
ROS_HOSTNAME=localhost
ROS_MAVEN_REPOSITORY=https://github.com/rosjava/rosjava_mvn_repo/raw/master
ROSLISP_PACKAGE_DIRECTORIES=
ROS_DISTRO=kinetic
ROS_IP=localhost
ROS_HOME=/home/ak/.ros
ROS_ETC_DIR=/opt/ros/kinetic/etc/ros

I'm able to build the code but I'm stuck with the error when I rosrun the binary

[FATAL] [1525151060.907371740]: You must call ros::init() before creating the first NodeHandle
Couldn't find an AF_INET address for []
Couldn't find an AF_INET address for []
[ERROR] [1525151060.944339461]: [registerPublisher] Failed to contact master at [:0].  Retrying...
Couldn't find an AF_INET address for []
Couldn't find an AF_INET address for []
Couldn't find an AF_INET address for []
Couldn't find an AF_INET address for []

And yes, I'm running roscore in another terminal and bashrc is sourced in every terminal session that is running.

The other posts in the forum which look similar are quite different than in my case. Any help would be really appreciated. Thanks

edit retag flag offensive close merge delete

Comments

Do you have any global variables that are ROS types? Something like a ros::Time or other object?

gvdhoorn gravatar image gvdhoorn  ( 2018-05-01 02:54:45 -0500 )edit

No there are none with ros as global variables. This pastebin has the complete code

reverse3D gravatar image reverse3D  ( 2018-05-01 03:10:12 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-05-01 03:14:06 -0500

gvdhoorn gravatar image

updated 2018-05-01 03:14:39 -0500

This is a ROS type and it internally initialises other ROS types:

const tf::TransformListener tf_listener_;

I'm almost certain that is the cause of the error you are seeing. If you want to keep it in the global scope, you could use a pointer and initialise that in your main(..).

edit flag offensive delete link more

Comments

@gvdhoorn You are right. That was the problem. I somehow overlooked it. Thanks

reverse3D gravatar image reverse3D  ( 2018-05-01 03:28:46 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-05-01 00:24:04 -0500

Seen: 2,581 times

Last updated: May 01 '18