jsll / IROS2018-Hallucinating-Robots

IROS 2018 paper "Hallucinating Robots: Inferring Obstacle Distances from Partial Laser Measurements".
MIT License
3 stars 2 forks source link

implementation on robot #3

Open yani-rl-ai opened 2 years ago

yani-rl-ai commented 2 years ago

Hi @jsll and @fverdoja Thank you for sharing your project. Could you provide us the guidelines of implementation on robot or ROS?

fverdoja commented 2 years ago

Hi @ROSNovice Once you have your network trained, my suggestion would be to build a ros node that subscribes to a lidar topic, pass the data through the network, and then republishes the filtered lidar (i.e., the output of the network) on another topic.

Best, Francesco.

yani-rl-ai commented 2 years ago

Hi @fverdoja thank you for your answer. sorry i am new in ROS. i have seen several example to publish the filtered 2D lidar such as this link : http://wiki.ros.org/navigation/Tutorials/RobotSetup/Sensors , however, should we define the laser scan spec in advance? because we already got the filtered scan range from the network output. Maybe you can provide the technical example for deployment in ROS

Thank you

fverdoja commented 2 years ago

This is an example code for the re-publisher node:

import math

import numpy as np
import rospy
import torch as tc
from sensor_msgs.msg import LaserScan
from torch.autograd import Variable

class HallucinateLaser:
    def __init__(self):
        # change these to fit your laser scanner
        self.leftmost_data = 98
        self.rightmost_data = 440
        self.max_dist = 30.0

        # change this to fit your network
        self.net_input_size = 126.0
        self.net = <LOAD YOUR TRAINED NEURAL NETWORK>
        self.net.eval()

        # take these from launch file
        self.input_laser_scan = rospy.get_param("~input_laser_scan", " ")
        self.subscriber = rospy.Subscriber(
            self.input_laser_scan, LaserScan, self.callback, queue_size=1
        )
        self.hallucinatedLaserPub = rospy.Publisher(
            "hallucinatedLaser", LaserScan, queue_size=10
        )

    def callback(self, req):
        hallucinatedLaserMsg = req
        temp = np.array(hallucinatedLaserMsg.ranges)
        trimmed_laser = (
            temp[self.leftmost_data : self.rightmost_data] / self.max_dist
        )
        left = 0
        right = 0
        num_laser_points = len(trimmed_laser)
        for i in range(
            int(math.floor(num_laser_points / self.net_input_size))
        ):
            left = int(i * self.net_input_size)
            right = int((i + 1) * self.net_input_size)
            net_input = Variable(
                tc.Tensor(trimmed_laser[left:right])
                .unsqueeze(0)
                .unsqueeze(0)
                .cuda()
            )
            outputs = self.net(net_input)
            trimmed_laser[left:right] = outputs.cpu().data.squeeze()

        trimmed_laser[right:] = [0] * int(num_laser_points - right)
        temp[self.leftmost_data : self.rightmost_data] = (
            trimmed_laser * self.max_dist
        )
        hallucinatedLaserMsg.ranges = temp
        self.hallucinatedLaserPub.publish(hallucinatedLaserMsg)

    def main(self):
        rospy.spin()

if __name__ == "__main__":
    rospy.init_node("HallucinateLaser")
    h_laser = HallucinateLaser()
    h_laser.main()
yani-rl-ai commented 2 years ago

This is an example code for the re-publisher node:

import math

import numpy as np
import rospy
import torch as tc
from sensor_msgs.msg import LaserScan
from torch.autograd import Variable

class HallucinateLaser:
    def __init__(self):
        # change these to fit your laser scanner
        self.leftmost_data = 98
        self.rightmost_data = 440
        self.max_dist = 30.0

        # change this to fit your network
        self.net_input_size = 126.0
        self.net = <LOAD YOUR TRAINED NEURAL NETWORK>
        self.net.eval()

        # take these from launch file
        self.input_laser_scan = rospy.get_param("~input_laser_scan", " ")
        self.subscriber = rospy.Subscriber(
            self.input_laser_scan, LaserScan, self.callback, queue_size=1
        )
        self.hallucinatedLaserPub = rospy.Publisher(
            "hallucinatedLaser", LaserScan, queue_size=10
        )

    def callback(self, req):
        hallucinatedLaserMsg = req
        temp = np.array(hallucinatedLaserMsg.ranges)
        trimmed_laser = (
            temp[self.leftmost_data : self.rightmost_data] / self.max_dist
        )
        left = 0
        right = 0
        num_laser_points = len(trimmed_laser)
        for i in range(
            int(math.floor(num_laser_points / self.net_input_size))
        ):
            left = int(i * self.net_input_size)
            right = int((i + 1) * self.net_input_size)
            net_input = Variable(
                tc.Tensor(trimmed_laser[left:right])
                .unsqueeze(0)
                .unsqueeze(0)
                .cuda()
            )
            outputs = self.net(net_input)
            trimmed_laser[left:right] = outputs.cpu().data.squeeze()

        trimmed_laser[right:] = [0] * int(num_laser_points - right)
        temp[self.leftmost_data : self.rightmost_data] = (
            trimmed_laser * self.max_dist
        )
        hallucinatedLaserMsg.ranges = temp
        self.hallucinatedLaserPub.publish(hallucinatedLaserMsg)

    def main(self):
        rospy.spin()

if __name__ == "__main__":
    rospy.init_node("HallucinateLaser")
    h_laser = HallucinateLaser()
    h_laser.main()

Thank you, i will try

yani-rl-ai commented 2 years ago

hi @fverdoja sorry, i want to confirm and ask you again. for these following parameter self.leftmost_data = 98 self.rightmost_data = 440 is it the static value? because i think the leftmost_data or rightmost_data can be changed dynamically and depend on the obstacle distance to the robot.

i have implement your code and change the laser spec and using ros navigation stack for test the performance, but the inferencing result is not appear. it is like a default laser. i have change the topic into "/hallucinatedLaser"

fverdoja commented 2 years ago

I think these two parameters depend on your laser sensor. basically if your message from the laser is an 1D array with some zeros on both sides, you want leftmost_data and rightmost_data to correspond to where the zeros end and the actual message start on both sides.

Regarding why the result from your network is not being published, I am not sure. You should do some debugging. Are you replacing this line to incorporate your network? self.net = <LOAD YOUR TRAINED NEURAL NETWORK>

yani-rl-ai commented 2 years ago

this is my configuration import math import rospy import numpy as np from sensor_msgs.msg import LaserScan import nets as hn from torch.autograd import Variable from config import *

class HallucinateLaser: def init(self): self.leftmost_data = -119 self.rightmost_data = 119 self.max_dist = 30

change this to fit your network

    self.net_input_size = 126.0
    self.net_layer_sizes = [16,32,64,128]
    self.net_activation_gamma = 0.25
    self.noise = 0.0
    self.use_cuda = True
    self.net = hn.to_cuda(hn.AutoEnc(self.net_layer_sizes, self.net_activation_gamma), self.use_cuda)
    self.net_load_file = 'Net-4-n-1_0-f-22_02_01_013902.pt'
    self.net.load_state_dict(tc.load("%s%s" % (net_dump_folder, self.net_load_file)))
    self.net.eval()

    #change this to fit your network
    self.subscriber = rospy.Subscriber("/hsrb/base_scan",LaserScan, self.callback, queue_size=1
    )
    self.hallucinatedLaserPub = rospy.Publisher("hallucinatedLaser", LaserScan, queue_size=10)
yani-rl-ai commented 2 years ago

this is my laser scan spec. i filled the leftmost and rightmost based on angle_min and angle_max in degree. is it right? sorry for the inconvenience rostopic echo /hsrb/base_scan -n1 header: seq: 762 stamp: secs: 184 nsecs: 976000000 frame_id: "base_range_sensor_link" angle_min: -2.0999999046325684 angle_max: 2.0999999046325684 angle_increment: 0.015613382682204247 time_increment: 0.0 scan_time: 0.0 range_min: 0.05000000074505806 range_max: 30.0

fverdoja commented 2 years ago

the network setup looks good. For the left_most and right_most I don't think you can use negative numbers. If you see in the callback function, they are used as indeces for the array, so negative numbers don't do what you imagine there. I suggest, to start, you check what len(hallucinatedLaserMsg.ranges) is, and then you set self.left_most_data = 0 self.right_most_data = (basically to take the full laser array returned by the base_scan message) Then, once you see the network is working, if you see zeros at the two edges of the scan and want to remove them, set these two parameters accordingly.

yani-rl-ai commented 2 years ago

self.leftmost_data = 98 self.rightmost_data = 440 is the leftmost and rightmost value were got from this following dataset(input_test_data.txt)?

0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1.14 1.15 1.13 1.13 1.11 1.12 1.09 1.1 1.09 1.08 1.08 1.06 1.06 1.05 1.05 1.04 1.04 1.03 1.03 1.03 1.03 1.04 1.05 1.06 1.08 1.09 1.11 1.13 1.14 1.15 1.17 1.19 1.21 1.24 1.26 1.27 1.31 1.33 1.38 1.4 1.43 1.46 1.5 1.54 1.57 1.67 1.96 2.05 2.08 2.16 2.21 2.28 2.33 2.42 2.48 2.56 2.65 2.74 2.84 2.94 3.05 3.18 3.3 3.47 3.63 3.81 4.01 4.24 4.5 4.76 5.1 5.47 5.89 6.53 7.35 7.99 8.33 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 29.96 14.59 29.96 29.96 29.96 29.96 9.58 9.03 8.54 8.15 8.11 29.96 7.21 7.02 6.43 6.18 5.94 5.72 5.51 5.34 5.15 4.99 4.84 4.69 4.56 4.43 4.33 4.22 4.22 4.22 4.47 4.55 4.57 4.57 4.59 6.12 3.41 3.38 3.38 3.37 3.32 3.26 3.2 3.15 3.09 3.03 2.99 2.95 2.89 2.85 2.81 2.72 2.6 2.57 2.53 2.5 2.47 2.43 2.41 2.37 2.34 2.32 2.29 2.26 2.25 2.22 2.18 2.16 2.14 2.12 2.1 2.07 2.05 2.02 2 1.97 1.97 1.94 1.93 1.91 1.9 1.88 1.86 1.84 1.82 1.81 1.8 1.77 1.76 1.75 1.74 1.72 1.71 1.7 1.68 1.65 1.65 1.65 1.63 1.61 1.61 1.6 1.59 1.57 1.58 1.55 1.55 1.54 1.53 1.51 1.51 1.51 1.49 1.48 1.47 1.47 1.46 1.46 1.45 1.45 1.44 1.43 1.43 1.42 1.41 1.42 1.41 1.41 1.4 1.38 1.39 1.37 1.38 1.36 1.37 1.35 1.34 1.35 1.34 1.33 1.34 1.34 1.33 1.33 1.32 1.32 1.31 1.31 1.31 1.3 1.31 1.3 1.31 1.31 1.31 1.3 1.29 1.29 1.28 1.28 1.28 1.27 1.28 1.3 1.28 1.27 1.28 1.29 1.3 1.29 1.29 1.29 1.29 1.3 1.3 1.31 1.31 1.31 1.3 1.3 1.3 1.3 1.3 1.31 1.31 1.32 1.34 1.31 1.32 1.32 1.33 1.33 1.33 1.34 1.34 1.34 1.34 1.34 1.35 1.35 1.35 1.36 1.36 1.36 1.36 1.37 1.37 1.38 1.38 1.4 1.39 1.4 1.41 1.4 1.41 1.43 1.42 1.44 1.44 1.45 1.45 1.45 1.46 1.47 1.49 1.49 1.49 1.49 1.51 1.52 1.53 1.53 1.53 1.55 1.56 1.56 1.58 1.59 1.59 1.61 1.62 1.62 1.65 1.65 1.66 1.66 1.68 1.7 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0

in my case, the zeros only from right-side the total laser is 721 then i follow your suggestion to set these two parameters based on where zeros end at the two edges of the scan to remove them. however, the inferencing is still not available

angle_min: -2.0999999046325684 angle_max: 2.0999999046325684 angle_increment: 0.005833333358168602 time_increment: 0.0 scan_time: 0.0 range_min: 0.05000000074505806 range_max: 30.0 ranges: [13.640088081359863, 13.63571834564209, 13.603841781616211, 13.616495132446289, 13.592864990234375, 13.619392395019531, 13.610077857971191, 13.636722564697266, 13.652769088745117, 13.608863830566406, 13.535581588745117, 13.541528701782227, 13.51353645324707, 13.55463981628418, 13.568707466125488, 13.544800758361816, 13.490998268127441, 13.492348670959473, 13.480875968933105, 13.491679191589355, 13.472570419311523, 13.517416000366211, 13.553033828735352, 13.552495956420898, 13.531534194946289, 13.53014087677002, 13.491179466247559, 13.458430290222168, 13.373006820678711, 13.373651504516602, 13.311089515686035, 13.331551551818848, 13.343230247497559, 13.349403381347656, 13.342023849487305, 13.322029113769531, 13.263051986694336, 13.33039379119873, 13.394386291503906, 13.40634822845459, 13.404475212097168, 13.389938354492188, 13.35141658782959, 13.345993995666504, 13.305278778076172, 13.323225975036621, 13.308141708374023, 13.294010162353516, 13.25691032409668, 13.272321701049805, 13.271202087402344, 13.26016616821289, 13.21347713470459, 13.260992050170898, 13.293734550476074, 13.310738563537598, 13.316912651062012, 13.288744926452637, 13.247114181518555, 13.223627090454102, 13.161188125610352, 13.146045684814453, 13.098775863647461, 13.091434478759766, 13.066576957702637, 13.084749221801758, 13.10601806640625, 13.107184410095215, 13.084745407104492, 13.112173080444336, 13.143909454345703, 13.15814208984375, 13.162620544433594, 13.17041301727295, 13.173871994018555, 13.18625259399414, 13.177277565002441, 13.21247673034668, 13.246828079223633, 13.244004249572754, 13.223444938659668, 13.252437591552734, 13.263998985290527, 13.233525276184082, 13.1583251953125, 13.298447608947754, 13.452557563781738, 13.532559394836426, 13.621935844421387, 13.725418090820312, 13.84946060180664, 13.92530632019043, 14.000405311584473, 14.109827995300293, 14.260503768920898, 14.274345397949219, 14.275782585144043, 14.22778034210205, 14.173589706420898, 14.16812515258789, 14.110536575317383, 14.09040355682373, 14.043425559997559, 13.976273536682129, 13.852662086486816, 13.790157318115234, 13.643625259399414, 13.58150577545166, 13.439559936523438, 13.588839530944824, 13.67479419708252, 14.413590431213379, 15.18506908416748, 15.458525657653809, 15.734947204589844, 15.667791366577148, 15.565301895141602, 15.63829231262207, 15.952041625976562, 15.918128967285156, 15.782033920288086, 15.693132400512695, 15.569435119628906, 16.08780288696289, 17.07183265686035, 17.716596603393555, 18.53413963317871, 18.566852569580078, 18.442106246948242, 18.445898056030273, 18.450965881347656, 18.551959991455078, 18.561677932739258, 18.603769302368164, 18.603952407836914, 18.713350296020508, 18.74785614013672, 18.758485794067383, 18.767839431762695, 18.848983764648438, 18.780771255493164, 18.775842666625977, 18.741744995117188, 18.81578826904297, 18.823530197143555, 18.878978729248047, 18.887893676757812, 18.971694946289062, 18.892353057861328, 18.912559509277344, 18.873472213745117, 18.982004165649414, 19.009607315063477, 19.049497604370117, 19.059463500976562, 19.09793472290039, 19.000505447387695, 18.983482360839844, 18.919837951660156, 18.991350173950195, 19.001333236694336, 19.027376174926758, 18.996158599853516, 19.032133102416992, 18.897546768188477, 18.90337371826172, 18.864360809326172, 18.89689826965332, 18.885969161987305, 18.830739974975586, 18.7141170501709, 18.69350814819336, 18.48473358154297, 18.4255313873291, 18.332408905029297, 18.347820281982422, 18.30662727355957, 18.21170997619629, 18.003753662109375, 17.940462112426758, 17.717334747314453, 17.82796287536621, 17.879291534423828, 17.915573120117188, 17.881927490234375, 17.791162490844727, 17.644758224487305, 17.641639709472656, 17.39107894897461, 17.323497772216797, 17.247488021850586, 17.139469146728516, 17.0394344329834, 17.02081298828125, 16.90065574645996, 16.845497131347656, 16.62717056274414, 16.598297119140625, 16.477642059326172, 16.396739959716797, 16.29193878173828, 16.289243698120117, 16.152271270751953, 16.02471923828125, 15.520769119262695, 15.364079475402832, 15.184927940368652, 14.820164680480957, 14.506247520446777, 14.494318962097168, 14.416900634765625, 14.337358474731445, 14.156826972961426, 14.101336479187012, 13.995468139648438, 13.937347412109375, 13.815669059753418, 13.768203735351562, 13.65167236328125, 13.815661430358887, 13.948869705200195, 14.039288520812988, 14.138063430786133, 14.187832832336426, 14.215356826782227, 14.198972702026367, 14.121912956237793, 14.143597602844238, 14.123519897460938, 14.159183502197266, 14.181851387023926, 14.266666412353516, 14.334593772888184, 14.343283653259277, 14.325817108154297, 14.302109718322754, 14.206249237060547, 14.141003608703613, 14.049139022827148, 14.114226341247559, 14.142845153808594, 14.131722450256348, 14.060697555541992, 14.114128112792969, 14.11965560913086, 14.140610694885254, 14.14222526550293, 14.142902374267578, 14.099212646484375, 14.143198013305664, 14.363685607910156, 14.572305679321289, 15.138775825500488, 15.071615219116211, 15.008940696716309, 15.057106018066406, 15.05899429321289, 15.090886116027832, 15.109391212463379, 15.138208389282227, 15.113533973693848, 15.160507202148438, 15.204211235046387, 15.246603965759277, 15.286263465881348, 15.318419456481934, 15.385143280029297, 15.449734687805176, 15.4762544631958, 15.470779418945312, 15.4702787399292, 15.487849235534668, 15.49127197265625, 15.500848770141602, 15.525525093078613, 15.568572998046875, 15.55656909942627, 15.655903816223145, 15.741235733032227, 15.719036102294922, 15.701034545898438, 15.715621948242188, 15.677440643310547, 15.671187400817871, 15.662114143371582, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, 20.313507080078125, 20.262659072875977, 20.361736297607422, 20.457679748535156, 20.487594604492188, 20.46409034729004, 20.429893493652344, 20.517995834350586, 20.527856826782227, 20.443565368652344, 20.389110565185547, 20.431636810302734, 20.36197853088379, 20.258056640625, 20.008808135986328, 19.896699905395508, 19.691139221191406, 19.32703971862793, 18.988784790039062, 18.72121810913086, 18.2089786529541, 17.979812622070312, 17.424013137817383, 17.28275489807129, 17.1093692779541, 16.896080017089844, 16.65719223022461, 16.56320571899414, 16.409210205078125, 16.36155128479004, 16.057106018066406, 15.944316864013672, 15.866190910339355, 15.752116203308105, 15.690693855285645, 15.721084594726562, 15.668241500854492, 15.608519554138184, 15.519917488098145, 15.605944633483887, 15.633766174316406, 15.674128532409668, 15.713136672973633, 15.70695686340332, 15.677003860473633, 15.648411750793457, 15.581903457641602, 15.639434814453125, 15.679607391357422, 15.690459251403809, 15.706889152526855, 15.74583625793457, 15.79216194152832, 15.829116821289062, 15.899577140808105, 15.952630996704102, 15.952786445617676, 16.008846282958984, 16.080562591552734, 16.027929306030273, 15.96810245513916, 15.96523380279541, 15.929697036743164, 15.98998737335205, 16.04145050048828, 16.12095069885254, 16.175884246826172, 16.197755813598633, 16.196521759033203, 16.220365524291992, 16.18982696533203, 16.198040008544922, 16.165563583374023, 16.18143653869629, 16.184711456298828, 16.199352264404297, 16.175580978393555, 16.17543601989746, 16.116674423217773, 16.16518783569336, 16.17611312866211, 16.219633102416992, 16.267837524414062, 16.286104202270508, 16.28965187072754, 16.33203887939453, 16.340547561645508, 16.341602325439453, 16.2838134765625, 16.262096405029297, 16.232757568359375, 16.20779037475586, 16.15608787536621, 16.161354064941406, 16.048677444458008, 16.0180721282959, 15.982060432434082, 15.901030540466309, 15.866044044494629, 15.880962371826172, 15.867138862609863, 15.849331855773926, 15.769938468933105, 15.740389823913574, 15.669320106506348, 15.65778636932373, 15.673493385314941, 15.647782325744629, 15.598420143127441, 15.58816146850586, 15.503683090209961, 15.507295608520508, 15.510353088378906, 15.481395721435547, 15.481424331665039, 15.498780250549316, 15.489814758300781, 15.461262702941895, 15.394414901733398, 15.346416473388672, 15.229766845703125, 15.243816375732422, 15.231119155883789, 15.253584861755371, 15.30473804473877, 15.254467010498047, 15.222718238830566, 15.099289894104004, 14.977161407470703, 15.005088806152344, 14.961658477783203, 14.989619255065918, 14.953214645385742, 14.957240104675293, 14.917658805847168, 14.894512176513672, 14.863232612609863, 14.863537788391113, 14.851344108581543, 14.879072189331055, 14.851377487182617, 14.812739372253418, 14.764561653137207, 14.771637916564941, 14.774941444396973, 14.781584739685059, 14.766420364379883, 14.749178886413574, 14.750597953796387, 14.799290657043457, 14.804256439208984, 14.80276107788086, 14.813791275024414, 14.774077415466309, 14.737326622009277, 14.741251945495605, 14.697264671325684, 14.678321838378906, 14.676382064819336, 14.677775382995605, 14.6948823928833, 14.690958023071289, 14.651082992553711, 14.635613441467285, 14.599995613098145, 14.613102912902832, 14.596113204956055, 14.58816909790039, 14.59610652923584, 14.585169792175293, 14.555455207824707, 14.537692070007324, 14.495440483093262, 14.5243558883667, 14.550195693969727, 14.585408210754395, 14.613726615905762, 14.572880744934082, 14.515340805053711, 14.537874221801758, 14.534934043884277, 14.52786636352539, 14.512483596801758, 14.479331016540527, 14.474106788635254, 14.485054969787598, 14.468822479248047, 14.44304370880127, 14.372756958007812, 14.385601043701172, 14.393026351928711, 14.39946460723877, 14.403512954711914, 14.381796836853027, 14.301263809204102, 14.255064964294434, 14.180814743041992, 14.217284202575684, 14.222901344299316, 14.217047691345215, 14.231809616088867, 14.261174201965332, 14.250304222106934, 14.195830345153809, 14.09189224243164, 14.083921432495117, 14.046738624572754, 14.132942199707031, 14.187934875488281, 14.155778884887695, 14.085654258728027, 14.080023765563965, 14.060748100280762, 14.09589958190918, 14.106659889221191, 13.990447044372559, 13.89411449432373, 13.908625602722168, 13.88393497467041, 13.853707313537598, 13.778085708618164, 13.769220352172852, 13.734280586242676, 13.679971694946289, 13.620885848999023, 13.578545570373535, 13.483328819274902, 13.51291561126709, 13.540216445922852, 13.560580253601074, 13.568746566772461, 13.551743507385254, 13.52275276184082, 13.51569652557373, 13.470691680908203, 13.484994888305664, 13.479546546936035, 13.434911727905273, 13.351645469665527, 13.326980590820312, 13.278674125671387, 13.261556625366211, 13.204487800598145, 13.293249130249023, 13.376957893371582, 13.390046119689941, 13.388555526733398, 13.470833778381348, 13.51994514465332, 13.533014297485352, 13.643352508544922, 13.723287582397461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3324223756790161]

fverdoja commented 2 years ago

Yeah the left_most and right_most correspond to that file. In your case, you can set left_most to 0 and right_most to where data ends and zeros begin.

Regarding why inference is not working I don't know how to help you really, since it seems most likely related to the network.

yani-rl-ai commented 2 years ago

Hi @fverdoja thank you very much for always reply my question. i will try again. when i read your paper again, you used three 2D SICK S300 safety laser scanners. and i used toyota HSR that only have 1 hokuyo laser scanner. i am not sure it is because of the number of the laser in robot or the due to the network. i will investigate by myself.

yani-rl-ai commented 2 years ago

hi @fverdoja sorry for inconvenience, i would like to ask again. Did you tried this trained network using another lidar with different configuration. in your paper, you were using three 2D SICK S300. I wonder if i am using the different 2D Lidar, maybe i should collect new dataset.

fverdoja commented 2 years ago

Hi @ROSNovice I'm sorry, we tried our network only with that one setup you mention. It's possible that if your setup is very different than our, you might need to retrain on data more similar to the one of your sensors.