Publishing rate decreases when multiple nodes are publishing
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
how to connect sensors to Raspberry Pi?(usb or uart or ...)
they're connected via UART
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
Sorry, how do you edit usb latency?
firs install set serial(sudo apt-get install setserial) and use this command:
also you can edit manually by edit this file /sys/bus/usb-serial/devices/ttyUSB<usb number="">/latency_timer