Number of threads keep increasing in htop when running my python ROS node with 2 threads

asked 2022-11-28 14:37:02 -0500

Hulkthehunter gravatar image

I am writing a ROS node to read CAN data (linear x speed, and direction of motion i.e. rev or fwd) from my vehicle and my steer-by-wire system (encoder data for angular z). Both CAN interfaces are on separate CAN bus. I am using that data to generate odometry. We will call this node odom node.The odom node has 2 threads : one thread to generate linear velocity and another one to generate angular z velocity. The node also has a publisher for each of those parameters as well.

I also have a planning algorithm that works fine without the odom node, however, when I run my planning algorithm with my odom node, the planning algorithm crashes.

I opened up htop to see if its some sort of memory issue, I noticed that while the odom node is running, the number of threads keep on increasing (please refer to the image attached, 10740 threads).

image description

#!/usr/bin/env python3

import cantools
import can
from pprint import pprint
import rospy
from geometry_msgs.msg import Twist 
import numpy as np
import fixedint
import std_msgs.msg
from std_msgs.msg import Float64
from nav_msgs.msg import Odometry 
import math
import threading
import unittest

db = cantools.database.load_file('dbc_files/kia.dbc')
vehicle_can_bus = can.interface.Bus('can0', bustype='socketcan')
steer_by_wire_can_bus = can.interface.Bus('can1', bustype="socketcan")

class Telemetry:

    def __init__(self, linear_x, angular_z, encoder_angle,direction):

        self.linear_x = linear_x 
        self.angular_z = angular_z
        self.encoder_angle = encoder_angle
        self.direction = direction

        try : 

            self.linear_rate = rospy.get_param('~linear_vel_rate')
            self.angular_rate = rospy.get_param('~angular_vel_rate')

        except KeyError:
            print ("Could not set angular and linear thread rate parameters!!!")


        rospy.Timer(rospy.Duration(1.0 / self.linear_rate), self.linear_velocity_loop)
        rospy.Timer(rospy.Duration(1.0 / self.angular_rate), self.angular_velocity_loop)


    def linear_velocity_loop(self,event): 

        while not rospy.is_shutdown() : 

            # reader = can.BufferedReader()
            # notifier = can.Notifier(vehicle_can_bus, [reader], 10) # bus, listeners, time
            # message = reader.get_message(10) # timeout
            # if (message.arbitration_id == 213786525):
            #     rospy.loginfo_throttle((1/10),message.arbitration_id)

            message = vehicle_can_bus.recv()


            if message.arbitration_id == 317284680: # ID of ShtlDisp
                 # this message will print every 0.05 seconds (1/20)
                rospy.loginfo_throttle((1/10), "Shuttle msg")
                shuttle_data = db.decode_message('ShtlDisp', message.data)
                ShtlSymbol = shuttle_data['ShtlSymbol']

                if (ShtlSymbol == 3) :  # if the shuttle is in rev position, ShtlSymbol == 1 is fwd, 2 is neutral, 3 is rev
                    self.direction  = -1
                    # rospy.loginfo("The shuttle status is reverse")

                elif ShtlSymbol == 1 :
                    self.direction  = 1
                    # rospy.loginfo("The shuttle status is forward")

                # else:
                    # self.direction  = 0
                    # rospy.loginfo("The shuttle status is neutral")


            if message.arbitration_id == 213786525: # ID converted to HEX. Make sure if CAN ID is 19 or 29 bit. ID of DbmSpeedDisplay 213786525

                rospy.loginfo_throttle((1/10), "Received speed from CAN")

                readable_data = db.decode_message('DbmSpeedDisplay', message.data)
                SpeedDisplay_H = readable_data['SpeedDisplay_H']
                SpeedDecimalPoint = readable_data['SpeedDecimalPoint']
                SpeedDisplay_L = readable_data['SpeedDisplay_L'] # to kmph (dib by 100) and then m/sec (div 3.6)
                PtoRpm_H = readable_data['PtoRpm_H']
                PtoRpm_L = readable_data['PtoRpm_L']


                if (SpeedDisplay_H == 0): 
                    if (SpeedDisplay_L < 0):
                        SpeedDisplay_L =  255 + SpeedDisplay_L

                if (SpeedDisplay_H == 1): 
                    if (SpeedDisplay_L > 0):
                        SpeedDisplay_L =  255 + SpeedDisplay_L

                velocity = SpeedDisplay_L*self.direction
                self.linear_x = velocity/(100*3 ...
(more)
edit retag flag offensive close merge delete