Publishing rate decreases when multiple nodes are publishing

asked 2018-09-21 20:20:16 -0500

EDJ14 gravatar image

I have 4 nodes running on a Raspberry Pi that collect data from an IMU, GPS, and 2 potentiometers, and publish to a single rosbag. When only the GPS node is running, the GPS node will publish at 1 Hz. But when the potentiometer node is also running at the same time this decreases to about .3 Hz. The other sensors experience a similar reduction when all nodes are running simultaneously.

Is there a way to modify the potentiometer node script below to prevent this?

#! /usr/bin/env python

import rospy
from std_msgs.msg import UInt32
import Adafruit_ADS1x15

adc = Adafruit_ADS1x15.ADS1015()
GAIN = 1
adc.start_adc(0, gain=GAIN)

def talker():
    pub = rospy.Publisher('steerangle', UInt32, queue_size=50)
    rospy.init_node('talker', anonymous=True)
    rate = rospy.Rate(5)
    while not rospy.is_shutdown():
        value = adc.get_last_result()
        rospy.loginfo(value)
        pub.publish(value)
        rate.sleep()

if __name__ == '__main__':
    try:
        talker()
    except rospy.ROSInterruptException:
        pass
edit retag flag offensive close merge delete

Comments

how to connect sensors to Raspberry Pi?(usb or uart or ...)

Hamid Didari gravatar image Hamid Didari  ( 2018-09-22 23:20:29 -0500 )edit

they're connected via UART

EDJ14 gravatar image EDJ14  ( 2018-09-24 01:01:36 -0500 )edit

maybe your pi bus is to busy when you connect several sensor to board , i have same problem with usb(i use ft232 to convert uart to usb) i solve my problem by edit usb latency

Hamid Didari gravatar image Hamid Didari  ( 2018-09-24 02:13:03 -0500 )edit

Sorry, how do you edit usb latency?

EDJ14 gravatar image EDJ14  ( 2018-09-24 02:34:57 -0500 )edit

firs install set serial(sudo apt-get install setserial) and use this command:

$setserial /dev/<tty_name> low_latency

also you can edit manually by edit this file /sys/bus/usb-serial/devices/ttyUSB<usb number="">/latency_timer

Hamid Didari gravatar image Hamid Didari  ( 2018-09-24 03:20:44 -0500 )edit