微信公众号搜"智元新知"关注
微信扫一扫可直接关注哦!

使用 Nvidia Jetson Nano 和 Sphero RVR 在 ROS Melodic 上出现“致命的 Python 错误:无法从堆栈溢出中恢复”

如何解决使用 Nvidia Jetson Nano 和 Sphero RVR 在 ROS Melodic 上出现“致命的 Python 错误:无法从堆栈溢出中恢复”

我想要做的很简单:我尝试通过“cmd_vel”主题远程控制 Sphero RVR,并从 sphero 节点(IMU、里程计等)接收数据。该代码改编自 ROS2 变体,该变体似乎可以很好地做到这一点。

我使用的是 Jetson Nano A02 板。我也在使用 ROS Melodic 和 Python 3.6.9,这意味着我不能真正舒适地使用 asyncio sphero_sdk 变体,它似乎工作得更好,因此我使用“观察者”变体。该代码大量改编自编写了可以正常运行的 ROS2 脚本的人。

即使我运行 Sphero SDK 代码示例中的一些示例时也会发生错误,尽管错误的发生相当不一致,并且通常在我让脚本运行更长时间时发生。

如果我删除以下行:“self.rvr.sensor_control.start(interval=100)”,该错误似乎不再发生,该行负责在给定时间段发送传感器数据。

作为参考,这是 sphero_sdk 库:https://github.com/sphero-inc/sphero-sdk-raspberrypi-python

这是 sphero 线程的代码(尽管即使在运行一些更简单的示例时也会发生错误,例如:https://sdk.sphero.com/docs/how_to/raspberry_pi/rp_python_how_to/#sensor-streaming-multi-sensor-stream-1):

#!/usr/bin/python3
#=========== Classic Python libraries ======#
from math import pi
import os
import sys
import time 
from threading import Thread

#=========== Sphero libraries ==============#
from sphero_sdk import SpheroRvrObserver
from sphero_sdk import RvrStreamingServices
from sphero_sdk import ControlSystemTypesEnum
from sphero_sdk import ControlSystemIdsEnum
from sphero_sdk import SpheroRvrTargets
from sphero_sdk import BatteryVoltageStatesEnum as VoltageStates

#=========== ROS libraries =================#
import tf2_ros
import tf
import rospy
import geometry_msgs.msg 
from geometry_msgs.msg import PoseWithCovariance
from geometry_msgs.msg import Pose
from geometry_msgs.msg import TwistWithCovariance
from geometry_msgs.msg import Twist
from geometry_msgs.msg import Point
from geometry_msgs.msg import Quaternion
from geometry_msgs.msg import Vector3
from nav_msgs.msg import odometry
from sensor_msgs.msg import Imu
from std_msgs.msg import Header

def echo_handler(echo_response):
    print('Echo response: ',echo_response)


def get_nordic_main_application_version_handler(nordic_main_application_version):
    print('nordic main application version (target 1): ',nordic_main_application_version)


def get_st_main_application_version_handler(st_main_application_version):
    print('ST main application version (target 2): ',st_main_application_version)


def battery_percentage_handler(battery_percentage):
    print('Battery percentage: ',battery_percentage)


def battery_voltage_handler(battery_voltage_state):
    print('Voltage state: ',battery_voltage_state)

    state_info = '[{},{},{}]'.format(
        '{}: {}'.format(VoltageStates.unkNown.name,VoltageStates.unkNown.value),'{}: {}'.format(VoltageStates.ok.name,VoltageStates.ok.value),'{}: {}'.format(VoltageStates.low.name,VoltageStates.low.value),'{}: {}'.format(VoltageStates.critical.name,VoltageStates.critical.value)
    )
    print('Voltage states: ',state_info)


class SpheroThread(Thread):
    def __init__(self):
        #================ Thread parameters ================#
        print("Initializing SpheroThread")
        super(SpheroThread,self).__init__()
        self.daemon = True
        self._running = True

        #================ Sphero parameters ================#
        #=================== and start up ==================#
        # may be changed
        self.rvr = SpheroRvrObserver()
        # Not really "components",but a plethora of things.
        self.components_dict = {}
        self.components_dict['uart_port'] = '/dev/ttyTHS1'
        self.components_dict['cmd_vel'] = 'cmd_vel'
        self.components_dict['imu_link'] = 'imu_link'
        self.components_dict['imu'] = 'IMU'
        self.components_dict['odom'] = 'odom'
        self.components_dict['base_link'] = 'base_link'
        self.components_dict['base_footprint'] = 'base_footprint'
        self.components_dict['laser'] = 'laser'

        self.received_components = set()

        #================== ROS parameters =================#
        rospy.Subscriber(self.components_dict['cmd_vel'],Twist,self.cmd_vel_cb)
        self.imu = Imu(header=Header(frame_id=self.components_dict['imu_link']))
        self.imu.orientation_covariance = [1e-6,.0,1e-6,1e-6]
        self.imu.angular_veLocity_covariance = [1e-6,1e-6]
        self.imu.linear_acceleration_covariance = [1e-6,1e-6]
        self.imu_pub = rospy.Publisher(self.components_dict['imu'],Imu,queue_size=5)

        self.acceleration = Vector3()

        self.position = Point()
        self.orientation = Quaternion()
        self.pose = Pose(
            position=self.position,orientation=self.orientation,)

        self.pose_with_covariance = PoseWithCovariance(pose=self.pose)
        self.linear = Vector3()
        self.angular = Vector3()
        self.twist = Twist(linear=self.linear,angular=self.angular)
        self.twist_with_covariance = TwistWithCovariance(twist=self.twist)
        self.odom = odometry(
            pose=self.pose_with_covariance,twist=self.twist_with_covariance,header=Header(
                frame_id=self.components_dict['odom'],),child_frame_id=self.components_dict['base_footprint']
        )
        self.pub_odom = rospy.Publisher(self.components_dict['odom'],odometry,queue_size=5)
        self.odom_trans = geometry_msgs.msg.TransformStamped()
        self.odom_trans.header.frame_id = self.components_dict['odom']
        self.odom_trans.child_frame_id = self.components_dict['base_footprint']

        self.laser_trans = geometry_msgs.msg.TransformStamped()
        self.laser_trans.header.frame_id = self.components_dict['base_link']
        self.laser_trans.child_frame_id = self.components_dict['laser']
        self.laser_trans.transform.translation.x = 0.05
        self.laser_trans.transform.translation.y = 0.0
        self.laser_trans.transform.translation.z = 0.10
        self.laser_trans.transform.rotation.x = 0.0
        self.laser_trans.transform.rotation.y = 0.0
        self.laser_trans.transform.rotation.z = 0.0
        self.laser_trans.transform.rotation.w = 1.0

        self.footprint_trans = geometry_msgs.msg.TransformStamped()
        self.footprint_trans.header.frame_id = self.components_dict['base_footprint']
        self.footprint_trans.child_frame_id = self.components_dict['base_link']
        self.footprint_trans.transform.translation.x = 0.0
        self.footprint_trans.transform.translation.y = 0.0
        self.footprint_trans.transform.translation.z = 0.0
        self.footprint_trans.transform.rotation.x = 0.0
        self.footprint_trans.transform.rotation.y = 0.0
        self.footprint_trans.transform.rotation.z = 0.0
        self.footprint_trans.transform.rotation.w = 1.0

        self.imu_trans = geometry_msgs.msg.TransformStamped()
        self.imu_trans.header.frame_id = self.components_dict['base_link']
        self.imu_trans.child_frame_id = self.components_dict['imu_link']
        self.imu_trans.transform.translation.x = 0.0
        self.imu_trans.transform.translation.y = 0.0
        self.imu_trans.transform.translation.z = 0.0
        self.imu_trans.transform.rotation.x = 0.0
        self.imu_trans.transform.rotation.y = 0.0
        self.imu_trans.transform.rotation.z = 0.0
        self.imu_trans.transform.rotation.w = 1.0

        self.br = tf.Transformbroadcaster()

    def sphero_init(self):
        '''
        Check and an additional echo ping.
        '''
        self.rvr.wake()
        rospy.sleep(2)
        self.rvr.reset_yaw()
        self.rvr.reset_locator_x_and_y()
        self.rvr.drive_control.reset_heading()

        control_system_type = ControlSystemTypesEnum.control_system_type_rc_drive
        controller_id = ControlSystemIdsEnum.rc_drive_slew_mode
        self.rvr.set_default_control_system_for_type(
            control_system_type = control_system_type,controller_id = controller_id)
        # set timeout for stopping
        self.rvr.set_custom_control_system_timeout(command_timeout=75)

        echo_response = self.rvr.echo(
            data=[0,1,2],handler=echo_handler,target=SpheroRvrTargets.primary.value
        )

        self.rvr.get_main_application_version(
            handler=get_nordic_main_application_version_handler,target=SpheroRvrTargets.primary.value
        )
        rospy.sleep(0.5)

        self.rvr.get_main_application_version(
            handler=get_st_main_application_version_handler,target=SpheroRvrTargets.secondary.value
        )

        self.rvr.get_battery_percentage(handler=battery_percentage_handler)

        rospy.sleep(0.5)

        self.rvr.get_battery_voltage_state(handler=battery_voltage_handler)

        rospy.sleep(0.5)



    def check_if_need_to_send_msg(self,component):
        self.received_components.update(component)
        if self.received_components >= {'locator','quaternion','gyroscope','veLocity','accelerometer'}:
            self.received_components.clear()
            #self.rate = rospy.Rate(20)
            try:
                self.odom.header.stamp = rospy.Time.Now()
                self.pub_odom.publish(self.odom)

                self.odom_trans.header.stamp = self.odom.header.stamp

                self.odom_trans.transform.translation.x = self.position.x
                self.odom_trans.transform.translation.y = self.position.y
                self.odom_trans.transform.translation.z = self.position.z

                self.odom_trans.transform.rotation = self.orientation

                self.br.sendTransformMessage(self.odom_trans)

                self.laser_trans.header.stamp = self.odom.header.stamp
                self.br.sendTransformMessage(self.laser_trans)

                self.footprint_trans.header.stamp = self.odom.header.stamp
                self.br.sendTransformMessage(self.footprint_trans)

                self.imu.header.stamp = self.odom.header.stamp
                self.imu.orientation = self.orientation
                self.imu.linear_acceleration = self.acceleration
                self.imu.angular_veLocity = self.angular

                self.imu_pub.publish(self.imu)

                self.imu_trans.header.stamp = self.odom.header.stamp
                self.br.sendTransformMessage(self.imu_trans)
                #self.rate.sleep()
            except Exception as e:
                print("Exception publishing transformations: " + str(e))


    def sphero_handler(self,data):
        #print("In sphero_handler...")
        try:
            received = set()
            if 'Locator' in data:
                received.add('locator')
                # Sphero see forward towards Y as opposed to ROS,# which see forward as X. Rotate 90 deg.
                self.position.x = data['Locator']['Y']
                self.position.y = -data['Locator']['X']
                self.position.z = 0.0

            if 'Quaternion' in data:
                received.add('quaternion')
                # Rotate 90 as per above.
                self.orientation.w = data['Quaternion']['W']
                self.orientation.x = data['Quaternion']['X']
                self.orientation.y = data['Quaternion']['Y']
                self.orientation.z = -data['Quaternion']['Z']

            if 'gyroscope' in data:
                received.add('gyroscope')
                # convert to radians
                self.angular.x = data['gyroscope']['X'] * 2.0 * pi / 360.0
                self.angular.y = data['gyroscope']['Y'] * 2.0 * pi / 360.0
                self.angular.z = data['gyroscope']['Z'] * 2.0 * pi / 360.0

            if 'VeLocity' in data:
                received.add('veLocity')
                self.linear.x = data['VeLocity']['X']
                self.linear.y = data['VeLocity']['Y']

            if 'Accelerometer' in data:
                received.add('accelerometer')
                self.acceleration.x = data['Accelerometer']['X']
                self.acceleration.y = data['Accelerometer']['Y']
                self.acceleration.z = data['Accelerometer']['Z']

            self.check_if_need_to_send_msg(received)

        except Exception as e:
            print('Exception processing {}: {}'.format(data,e))

    
    def setup_listeners(self):
        try:
            self.rvr.sensor_control.add_sensor_data_handler(
                service=RvrStreamingServices.locator,handler=self.sphero_handler,)
            self.rvr.sensor_control.add_sensor_data_handler(
                service=RvrStreamingServices.quaternion,)
            self.rvr.sensor_control.add_sensor_data_handler(
                service=RvrStreamingServices.gyroscope,)
            self.rvr.sensor_control.add_sensor_data_handler(
                service=RvrStreamingServices.veLocity,)
            self.rvr.sensor_control.add_sensor_data_handler(
                service=RvrStreamingServices.accelerometer,)
            self.rvr.sensor_control.add_sensor_data_handler(
                service=RvrStreamingServices.imu,)

            self.rvr.on_will_sleep_notify(handler=self.sleep_handler)
            self.rvr.sensor_control.start(interval=100)

            # Just give it some time,since we're not running asyncio,we can't
            # schedule it nicely. :(
            rospy.sleep(1)
            print('Listeners in place')
        except Exception as e:
            msg = "Sphero thread setup error: " + str(e)
            raise Exception(msg)

    def sleep_handler(self):
        # Do not let the RVR sleep while we are connected
        try:
            self.rvr.wake()
        except Exception as e:
            self.logger.error('Exception processing sleep: {}'.format(e))

    def cmd_vel_cb(self,vel_cmd):
        print('help')
        angular_vel_deg = vel_cmd.angular.z * 360.0 / (2.0 * pi)
        self.rvr.drive_rc_si_units(
            linear_veLocity=vel_cmd.linear.x,yaw_angular_veLocity=angular_vel_deg,flags=0)


    #=================== STOP RUNNING THREAD ================#
    def stop(self): 
        self._running = False
        self.rvr.drive_stop()
        rospy.sleep(.5)
        self.rvr.sensor_control.stop()
        rospy.sleep(.5)
        self.rvr.sensor_control.clear()
        rospy.sleep(.5)
        self.rvr.restore_initial_default_control_systems()
        rospy.sleep(.5)
        self.rvr.restore_default_control_system_timeout()
        rospy.sleep(.5)
        self.rvr.close()


    #================= THEAD RUN GO BRRRR ===================#
    def run(self):
        self.sphero_init()
        self.setup_listeners()
        while self._running:
            pass

这是它所有荣耀中的错误

Fatal Python error: Cannot recover from stack overflow.

Thread 0x0000007f6affd1f0 (most recent call first):
  File "/home/userName/catkin_ws/src/sphero/src/new_sphero.py",line 358 in run
  File "/usr/lib/python3.6/threading.py",line 916 in _bootstrap_inner
  File "/usr/lib/python3.6/threading.py",line 884 in _bootstrap

Thread 0x0000007f6b7fe1f0 (most recent call first):
  File "/usr/lib/python3.6/threading.py",line 295 in wait
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/impl/tcpros_pubsub.py",line 429 in _run
  File "/usr/lib/python3.6/threading.py",line 864 in run
  File "/usr/lib/python3.6/threading.py",line 884 in _bootstrap

Current thread 0x0000007f6bfff1f0 (most recent call first):
  File "/usr/lib/python3.6/genericpath.py",line 130 in _splitext
  File "/usr/lib/python3.6/posixpath.py",line 129 in splitext
  File "/usr/lib/python3.6/logging/__init__.py",line 286 in __init__
  File "/usr/lib/python3.6/logging/__init__.py",line 1413 in makeRecord
  File "/usr/lib/python3.6/logging/__init__.py",line 1443 in _log
  File "/usr/lib/python3.6/logging/__init__.py",line 1320 in warning
  File "/usr/local/lib/python3.6/dist-packages/sphero_sdk-1.0.0-py3.6.egg/sphero_sdk/common/protocol/api_sphero_message.py",line 421 in from_buffer
  File "/usr/local/lib/python3.6/dist-packages/sphero_sdk-1.0.0-py3.6.egg/sphero_sdk/observer/client/dal/observer_parser.py",line 34 in __read
  File "/usr/local/lib/python3.6/dist-packages/sphero_sdk-1.0.0-py3.6.egg/sphero_sdk/observer/client/dal/observer_parser.py",line 51 in __read
  File "/usr/local/lib/python3.6/dist-packages/sphero_sdk-1.0.0-py3.6.egg/sphero_sdk/observer/client/dal/observer_parser.py",line 51 in __read
  ...

Thread 0x0000007f8356c1f0 (most recent call first):
  File "/usr/lib/python3.6/socket.py",line 205 in accept
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/impl/tcpros_base.py",line 154 in run
  File "/usr/lib/python3.6/threading.py",line 884 in _bootstrap

Thread 0x0000007f82d6b1f0 (most recent call first):
  File "/usr/lib/python3.6/threading.py",line 299 in wait
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/impl/registration.py",line 298 in run
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/impl/registration.py",line 276 in start
  File "/usr/lib/python3.6/threading.py",line 884 in _bootstrap

Thread 0x0000007f8256a1f0 (most recent call first):
  File "/usr/lib/python3.6/selectors.py",line 376 in select
  File "/usr/lib/python3.6/socketserver.py",line 236 in serve_forever
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rosgraph/xmlrpc.py",line 322 in _run
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rosgraph/xmlrpc.py",line 250 in run

Thread 0x0000007f85e53010 (most recent call first):
  File "/home/userName/catkin_ws/src/sphero/src/new_main.py",line 22 in <module>
Aborted

版权声明:本文内容由互联网用户自发贡献,该文观点与技术仅代表作者本人。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如发现本站有涉嫌侵权/违法违规的内容, 请发送邮件至 dio@foxmail.com 举报,一经查实,本站将立刻删除。