counter free hit invisible

Log in or sign up


USER:
PASS:

 
 
Forums
Tarek Taha :: Forums :: Sofware Support :: MRICP
 
<< Previous thread | Next thread >>
MRICP laser misallignment
Moderators: Tarek Taha, Gloden Wing
Author Post
Rikki Kho
Wed Jul 16 2008, 01:50AM
Registered Member #29
Joined: Wed Jul 16 2008, 12:24AM
Posts: 3
Hi Tarek,
I'm a student at Curtin University working on my final year project under the supervision of Jonathan Paxman. I'm trying to use MRICP as a mapping driver in the project.

When I start the Player server, the MRICP is able to plot the initial map of the environment. However as I move the robot using the VFH driver, I get the following error messages which are repeatedly printed on the screen:

WARNING: possible misalignment ICP: 1 - skipping scan
Detected Possible misalignment --- Skipping this Laser Set! Gate is:0.5

WARNING: possible misalignment ICP: 3 - skipping scan
Detected Possible misalignment --- Skipping this Laser Set! Gate is:0.5

I'm running Player 2.2.0 from SVN and stage 2.1.0.
Attached are the player configuration files and stage world files I used.

Thank You,
Rikki


mricp_test.tar
Back to top

Tarek Taha
Thu Jul 17 2008, 04:35AM

Registered Member #1
Joined: Sat May 05 2007, 07:02AM
Posts: 8
Hi Rikki,

  I had  a look at your example, the main problem with your demo is the Laser range which you specified as 2 meters. Given that your map is large, the 2 meter laser range will not be able to cover a lot of map walls per scan and thus majority of the laser scan returns a max range and hence the misalignment !!! I just modified the laser range to 4 meters  and tweaked few parameters :
driver
(
  name "mricp"
  provides ["position2d:1" "map:0"]
  requires ["position2d:0" "laser:0"]
  number_of_lasers 1
  laser0_ranges [-120 120]
  playerv_debug 0
  period 0.1
  MAXR 3.9
  MINR 0.05
  map_resolution 0.05
  map_saving_period 5
  map_size 16
  use_max_range 3.9
  sparse_scans_rate 3
  map_path "logs/"
  debug 0
  alwayson 1
  log 1
)
Reduce the sparse_scans_rate for an more accurate mapping (will result in higher CPU usage). Focus on getting accurate map at the beginning before tuning the performance. I attached a simple test i tried and it works resonably. From my experience MRICP works better in real test than in simulation due to the unique features that can be detected in real scenarios. One more thing, I would suggest that you use nd "nearnest diagram" driver instead of VFH.

Regards,
Tarek
Back to top

Rikki Kho
Thu Jul 17 2008, 08:16AM
Registered Member #29
Joined: Wed Jul 16 2008, 12:24AM
Posts: 3
Hi Tarek, I have tried the modifications to the MRICP parameters you suggested, but I am still getting the same laser misalignment messages I was getting previously. I have attached a few screenshots showing the problem. Screenshot-3.png shows the results where the map shows the initial surroundings of the robot. When the robot is moved the map is not updated with the new laser data. I found that if I comment out the "laser0_ranges [-120 120]" parameter, I do not get the laser misalignment messages. However, doing this generates a warning saying that there is an unhandled message for driver device. No map is produced, as shown in Screenshot-1.png. Rikki





[ Edited Thu Jul 17 2008, 08:54PM ]
Back to top

Tarek Taha
Thu Jul 17 2008, 10:36PM

Registered Member #1
Joined: Sat May 05 2007, 07:02AM
Posts: 8
Hi,
  MRICP can be tricky unless you know what you are doing, there are a lot of parameters and options that you need to adjust to get the results you want. The problem with your settings was that the starting location had to many MAX range returns. The misalignment warning comes when less than half of the laser points are successfully matched withing the assigned gates. To overcome this you can usually increase the gates size or simply ignore the max returns by adding use_max_range 0 in the driver configs. The laser0_range has nothing to do with the matching itself, it just specifies the laser unobstructed range and when you comment it the default range [-90 90] is used which in your specific case was giving less misalignments. Below is the modification to the configurations (i added few more configs that you might to tune later on):
driver
(
  name "mricp"
  provides ["position2d:1" "map:0"]
  requires ["position2d:0" "laser:0"]
  gate1 0.5
  gate2 0.05
  use_odom 1
  number_of_lasers 1
  laser0_ranges [-120 120]
  playerv_debug 0
  period 0.2
  MAXR 3.9
  MINR 0.05
  map_resolution 0.05
  map_saving_period 5
  map_size 16
  use_max_range 0
  sparse_scans_rate 1
  map_path "logs/"
  debug 0
  alwayson 1
  log 1
)






[/html]
Back to top

Rikki Kho
Fri Jul 18 2008, 02:19AM
Registered Member #29
Joined: Wed Jul 16 2008, 12:24AM
Posts: 3
Hi Tarek,

We modified the gate parameters in the configuration file and were able to generate a good map of the environment. Thank you for your time and suggestions, it was much appreciated.

Rikki


Back to top

Tarek Taha
Fri Jul 18 2008, 03:40AM

Registered Member #1
Joined: Sat May 05 2007, 07:02AM
Posts: 8
No worries, let me know if you encounter any more problems ...

Regards,
Tarek

[ Edited Fri Jul 18 2008, 03:40AM ]
Back to top

Yasir
Wed Jul 29 2009, 12:18PM
Registered Member #43
Joined: Wed Jul 29 2009, 12:13PM
Posts: 2
Hello Tarek.

I am also trying to use MRICP with my Hokuyo UTM30-LX scanner. It is giving me the same "misalignment" error and not building any maps. I have used most of your settings below except the ranges. Please help. Here are my settings:

driver
(
  name "mricp"
  provides ["position2d:3" "map:3"]
  requires ["position2d:0" "laser:0"]
  gate1 0.5
  gate2 0.05
  use_odom 1
  number_of_lasers 1
  laser0_ranges [-135 135]
  playerv_debug 0
  period 0.5
  MAXR 30.0
  MINR 0.05
  map_resolution 0.05
  map_saving_period 5
  map_size 22
  use_max_range 0
  sparse_scans_rate 1
  map_path "logs/"
  debug 0
  alwayson 1
  log 1
)

I am using Player 2.1.2 and Stage 2.1.1 stable.

Regards,
Yasir


[ Edited Wed Jul 29 2009, 12:19PM ]
Back to top

 

Jump:     Back to top

Syndicate this thread: rss 0.92 Syndicate this thread: rss 2.0 Syndicate this thread: RDF
Powered by e107 Forum System