Robotics StackExchange | Archived questions

Unable to Access Object Properties, ObjectStamped is not Iterable

Greetings.

Info

I am using:

Stacks/Packages

Turtlebot 3 w/ Jetson Nano
- LINUX UBUNTU 20.04, ROS NOETIC 1.15.14, ZED SDK (3.8.1) L4T 32.7 / JETPACK 4.6.1, CUDA 10.2
ZED 2i Camera

MASTER PC
- LINUX UBUNTU 20.04, ROS NOETIC 1.15.14, ZED SDK (3.8.1) UBUNTU 20.0 , CUDA 11.6

ENV VARIABLES

MASTER PC VARS
ROS_VERSION=1
ROS_PYTHON_VERSION=3
ROS_PACKAGE_PATH=/home/jsoltre1/catkin_ws/src:/opt/ros/noetic/share
ROSLISP_PACKAGE_DIRECTORIES=/home/jsoltre1/catkin_ws/devel/share/common-lisp
ROS_ETC_DIR=/opt/ros/noetic/etc/ros
ROS_MASTER_URI=http://192.168.0.28:11311
ROS_HOSTNAME=192.168.0.28
ROS_ROOT=/opt/ros/noetic/share/ros
ROS_DISTRO=noetic

TURTLEBOT VARS
ROS_VERSION=1
ROS_PYTHON_VERSION=3
ROS_PACKAGE_PATH=/opt/ros/noetic/share
ROSLISP_PACKAGE_DIRECTORIES=
ROS_ETC_DIR=/opt/ros/noetic/etc/ros
ROS_MASTER_URI=http://192.168.0.28:11311
ROS_HOSTNAME=192.168.0.30
ROS_ROOT=/opt/ros/noetic/share/ros
ROS_DISTRO=noetic

rospy, zed-ros-wrapper are my included packages used in this program.

Goal

I would like to make a simple program:

The turtlebot moves a linear distance, it looks for objects in it's field of view, and stops when it is near an object. - It finds an object. The Object's x position is used to defer the distance between the Turtlebot's Camera and the Object itself. - When the (moving) turtlebot crosses the threshold distance, the program will print a message and stop the robot's movement.

As of right now, I simply want the program to detect the object and return a message that states "Object (x), detect, position close by.".

MY CODE:

#! /usr/bin/env python3

from queue import Empty
from re import X
from shutil import move
from tkinter import Y
from turtle import distance, forward, position, speed

from numpy import empty
import rospy
#from geometry_msgs.msg import Twist, Point
#from nav_msgs.msg import Odometry
from zed_interfaces.msg import Object
from zed_interfaces.msg import ObjectsStamped

objects = ObjectsStamped()
postObjx = Object()

def callback(msg):
    while not rospy.is_shutdown():
        objXThreshold = 2.0

        for i in objects:
            if (objects[i].position[0] >= objThreshold):
                print("Object" + str(objects[i].label) + "detected, position close by.")

def listenerObjX():

    rospy.init_node('listenerObjx', anonymous = True)
    subObjlist = rospy.Subscriber('/zed2i/zed_node/obj_det/objects', ObjectsStamped, callback)
    #subZedOdom = rospy.Subscriber('/zed2i/zed_node/odom', callback)
    rospy.spin()

if __name__ == '__main__':
    listenerObjX()

Issue

MY CODE ERROR:

[ERROR] [1667845398.329518]: bad callback: <function callback at 0x7f5e1b22a280>
Traceback (most recent call last):
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/topics.py", line 750, in _invoke_callback
    cb(msg)
  File "turtlebotLinearObjDet.py", line 23, in callback
    for i in objects:
TypeError: 'ObjectsStamped' object is not iterable

I am confused.

The topic ObjectsStamped is to be an array that stores Objects that are seen and captured by the ZED Camera, and sent to the zedroswrapper as information. The topic Object, holds the unique properties of x, y, z and etc. As found in the ZED SDK's documentation.

https://www.stereolabs.com/docs/ros/object-detection/

How might I be able to access ObjectsStamped and use an Object's x position while my program is running? - Is my implementation incorrect? - How should I improve my program?

Thank You.

Asked by bigo on 2022-11-08 09:43:22 UTC

Comments

Answers