]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
rtl_sdr_strength: Increase bandwidth
authorErik Andresen <erik@vontaene.de>
Sat, 20 Apr 2019 06:01:40 +0000 (08:01 +0200)
committerErik Andresen <erik@vontaene.de>
Sat, 20 Apr 2019 06:01:40 +0000 (08:01 +0200)
scripts/rtl_sdr_strength.py

index 5e09c525c2c46b83678bdb605b7dd313dd386f84..cd1eab92578fa919705cad584440b145ec474ba3 100755 (executable)
@@ -15,7 +15,7 @@ tfBuffer = tf2_ros.Buffer()
 listener = tf2_ros.TransformListener(tfBuffer)
 regex_lq = re.compile("Link Quality=(\d*)/(\d*)")
 while not rospy.is_shutdown():
-       popen = subprocess.Popen("rtl_power -f 868.3M:868.4M:10k -g 42 -i 1".split(), stdout=subprocess.PIPE)
+       popen = subprocess.Popen("rtl_power -f 868.2M:868.5M:10k -g 42 -i 1".split(), stdout=subprocess.PIPE)
        while True:
                line = popen.stdout.readline()
                if line == "":