Robotics StackExchange | Archived questions

Node not inizialized (critical but ignorable error?)

(ROS Indigo)

Hi, this is my python script into my personal package into my catkin worskpace (catkinws/src/mypackage/scripts/webcam3.py) that subscribes to usb_cam topic and, after some openCV operations, displays the image again. It is derived from this tutorial

After some tries, all works (I have to launch usb_cam first). But the terminal shows 2 times this critical (red) error, then the script starts to work normally. The error is:

[ERROR] [WallTime: 1479636395.259304] bad callback: <bound method image_converter.callback of <__main__.image_converter instance at 0x7f30464af050>>
Traceback (most recent call last):
  File "/opt/ros/indigo/lib/python2.7/dist-packages/rospy/topics.py", line 720, in _invoke_callback
    cb(msg)
  File "/home/marcor/catkin_ws/src/my_package/scripts/webcam3.py", line 88, in callback
    self.image_pub.publish(self.bridge.cv2_to_imgmsg(cv_image, "bgr8"))
  File "/opt/ros/indigo/lib/python2.7/dist-packages/rospy/topics.py", line 848, in publish
    raise ROSException("ROS node has not been initialized yet. Please call init_node() first")
ROSException: ROS node has not been initialized yet. Please call init_node() first

What is the problem? Why it works anyway? If someone could answer I will be grateful. Below the relevant parts of the code (quite equal to the tutorial code)

#!/usr/bin/env python
from __future__ import print_function
import roslib
import sys
import rospy
import cv2
import numpy as np
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError


roslib.load_manifest('my_package')

class image_converter:

  def __init__(self):
    print(cv2.__version__)
    self.image_pub = rospy.Publisher("image_topic_2",Image)

    self.bridge = CvBridge()
    self.image_sub = rospy.Subscriber("usb_cam/image_raw",Image,self.callback)

  def callback(self,data):
    try:
      cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
    except CvBridgeError as e:
      print(e)

# SOME OPENCV LOCAL STUFF (not reported here to shorten the code)    

    (rows,cols,channels) = cv_image.shape
    if cols > 60 and rows > 60 :
      found, corners = cv2.findChessboardCorners(cv_image, (8,7),flags=cv2.CALIB_CB_FAST_CHECK)
      if found:

#OTHER OPENCV STUFF (not reported here to shorten the code) 

    cv2.imshow("Morpheus", cv_image)
    cv2.waitKey(3)

    try:
      self.image_pub.publish(self.bridge.cv2_to_imgmsg(cv_image, "bgr8"))
    except CvBridgeError as e:
      print(e)

def main(args):
  ic = image_converter()
  rospy.init_node('image_converter', anonymous=True)
  try:
    rospy.spin()
  except KeyboardInterrupt:
    print("Shutting down")
  cv2.destroyAllWindows()

if __name__ == '__main__':

    main(sys.argv)

Asked by marcoresk on 2016-11-20 05:26:20 UTC

Comments

Answers

You subscribe (in the image_converter constructor) before the node was initialized. The correct way is to just switch the two commands:

def main(args):
  rospy.init_node('image_converter', anonymous=True)
  ic = image_converter()

Asked by NEngelhard on 2016-11-20 05:44:00 UTC

Comments

Good idea, but now error message appears 1 time (instead of 2 before switching the two lines). Any other suggestion?

Asked by marcoresk on 2016-11-20 09:20:23 UTC

It runs without problem for me on indigo (the load_manifest is no longer needed).

Asked by NEngelhard on 2016-11-20 14:07:38 UTC