Skip to content

Commit

Permalink
Solved the localization problem using ACML in ROS
Browse files Browse the repository at this point in the history
  • Loading branch information
MikeS96 committed Jul 14, 2020
1 parent 5febd6d commit 09c36f8
Show file tree
Hide file tree
Showing 11 changed files with 114 additions and 12 deletions.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
controller_frequency: 10

TrajectoryPlannerROS:
max_vel_x: 1.0 #0.5
min_vel_x: -0.1 #0.01
max_vel_theta: 1.57 #1.5

min_in_place_vel_theta: 0.314

acc_lim_theta: 3.14
acc_lim_x: 2.0
acc_lim_y: 2.0

sim_time: 1.0

vx_samples: 5.0
vtheta_samples: 10.0

pdist_scale: 0.6 #0.6
gdist_scale: 0.8 #0.8
occdist_scale: 0.02

holonomic_robot: false
14 changes: 14 additions & 0 deletions localization/where_am_i/my_robot/config/costmap_common_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
map_type: costmap

obstacle_range: 1.0 # 2.0
raytrace_range: 2.0 # 3.0

transform_tolerance: 0.2 # 0.0

robot_radius: 0.3 # 0.0
inflation_radius: 0.5 # 0.0
cost_scaling_factor: 5.0

observation_sources: laser_scan_sensor

laser_scan_sensor: {sensor_frame: hokuyo, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
10 changes: 10 additions & 0 deletions localization/where_am_i/my_robot/config/global_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
global_costmap:
global_frame: map
robot_base_frame: robot_footprint
update_frequency: 2.0
publish_frequency: 2.0
width: 20.0
height: 20.0
resolution: 0.05
static_map: true
rolling_window: false
10 changes: 10 additions & 0 deletions localization/where_am_i/my_robot/config/local_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
local_costmap:
global_frame: odom
robot_base_frame: robot_footprint
update_frequency: 5.0
publish_frequency: 5.0
width: 10.0
height: 10.0
resolution: 0.05
static_map: false
rolling_window: true
26 changes: 23 additions & 3 deletions localization/where_am_i/my_robot/launch/amcl.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@

<launch>

<rosparam file="$(find my_robot)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find my_robot)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find my_robot)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find my_robot)/config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find my_robot)/config/base_local_planner_params.yaml" command="load" />

<!-- Map Server -->
<arg name="map_file" default="$(find my_robot)/maps/map.yaml"/>
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" />
Expand All @@ -13,9 +19,23 @@
<param name="base_frame_id" value="robot_footprint"/>
<param name="global_frame_id" value="map"/>

<!-- If you choose to define initial pose here -->
<param name="initial_pose_x" value="0.6"/>
<param name="initial_pose_y" value="-5.5"/>
<param name="transform_tolerance" value="0.5"/>

<!-- If you choose to define initial pose here -->
<param name="initial_pose_x" value="-5.5"/>
<param name="initial_pose_y" value="0.6"/>
</node>

<!-- Move Base -->
<node name="move_base" pkg="move_base" type="move_base" respawn="false" output="screen">
<param name="base_global_planner" value="navfn/NavfnROS" />
<param name="base_local_planner" value="base_local_planner/TrajectoryPlannerROS"/>

<rosparam file="$(find my_robot)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find my_robot)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find my_robot)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find my_robot)/config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find my_robot)/config/base_local_planner_params.yaml" command="load" />
</node>

</launch>
2 changes: 1 addition & 1 deletion localization/where_am_i/my_robot/maps/map.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
image: map.pgm
image: /home/sherlock/catkin_ws/src/my_robot/maps/map.pgm
resolution: 0.01
origin: [-15.0, -15.0, 0.0]
occupied_thresh: 0.65
Expand Down
41 changes: 33 additions & 8 deletions localization/where_am_i/my_robot/param/config.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@ Panels:
Expanded:
- /Global Options1
- /Status1
- /LaserScan1
Splitter Ratio: 0.5
Tree Height: 355
- Class: rviz/Selection
Expand Down Expand Up @@ -140,6 +139,32 @@ Visualization Manager:
Transport Hint: raw
Unreliable: false
Value: true
- Alpha: 0.699999988079071
Class: rviz/Map
Color Scheme: map
Draw Behind: false
Enabled: true
Name: Map
Topic: /map
Unreliable: false
Use Timestamp: false
Value: true
- Alpha: 1
Arrow Length: 0.30000001192092896
Axes Length: 0.30000001192092896
Axes Radius: 0.009999999776482582
Class: rviz/PoseArray
Color: 255; 25; 0
Enabled: true
Head Length: 0.07000000029802322
Head Radius: 0.029999999329447746
Name: PoseArray
Shaft Length: 0.23000000417232513
Shaft Radius: 0.009999999776482582
Shape: Arrow (Flat)
Topic: /particlecloud
Unreliable: false
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Expand Down Expand Up @@ -168,25 +193,25 @@ Visualization Manager:
Views:
Current:
Class: rviz/Orbit
Distance: 17.623416900634766
Distance: 12.774062156677246
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -0.0069710928946733475
Y: 0.01926247403025627
Z: 0.012315455824136734
X: -0.006360713392496109
Y: -4.929800987243652
Z: 0.680770993232727
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.7553980350494385
Pitch: 0.7053980827331543
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 6.028582572937012
Yaw: 0.1153959184885025
Saved: ~
Window Geometry:
Displays:
Expand All @@ -207,4 +232,4 @@ Window Geometry:
collapsed: false
Width: 1200
X: 67
Y: 32
Y: 27

0 comments on commit 09c36f8

Please sign in to comment.