Skip to content

Commit 351b1e5

Browse files
committed
Add GPS follower with ROS 2 control integration; EKF adjustments needed for improved performance on curve paths and turns (#10)
1 parent da15c39 commit 351b1e5

22 files changed

Lines changed: 901 additions & 20 deletions

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
cmake_minimum_required(VERSION 3.8)
2-
project(apricotka-robot-car)
2+
project(ros_sw)
33

44
# Default to C99
55
if(NOT CMAKE_C_STANDARD)

README.md

Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
# ROS Setup Instructions
2+
3+
## Install Required Packages
4+
5+
```bash
6+
sudo apt install ros-jazzy-navigation2
7+
sudo apt install ros-jazzy-nav2-bringup
8+
sudo apt install ros-jazzy-robot-localization
9+
sudo apt install ros-jazzy-mapviz
10+
sudo apt install ros-jazzy-mapviz-plugins
11+
sudo apt install ros-jazzy-tile-map
12+
```
13+
14+
## Setup ROS Environment
15+
16+
```bash
17+
source /opt/ros/jazzy/setup.bash
18+
```
19+
20+
## Create Workspace and Clone Repositories
21+
22+
```bash
23+
mkdir gps_ws
24+
cd gps_ws
25+
git clone -b 10-gps-navigation https://github.com/KPI-Rover/ros_sw.git
26+
git clone -b jazzy https://github.com/ros-navigation/navigation2_tutorials.git
27+
```
28+
29+
## Build the Workspace
30+
31+
```bash
32+
colcon build --symlink-install
33+
source install/setup.bash
34+
```
35+
36+
## Launch Simulation
37+
38+
```bash
39+
ros2 launch ros_sw launch_sim.launch.py use_rviz:=True use_mapviz:=True
40+
```
41+
42+
## Run GPS Waypoint Follower Demos
43+
44+
```bash
45+
ros2 run nav2_gps_waypoint_follower_demo interactive_waypoint_follower
46+
ros2 run nav2_gps_waypoint_follower_demo gps_waypoint_logger </path/to/yaml/file.yaml>
47+
ros2 run nav2_gps_waypoint_follower_demo logged_waypoint_follower </path/to/yaml/file.yaml>
48+
```
49+
50+
## Run Teleop Twist Keyboard
51+
52+
```bash
53+
ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args -r /cmd_vel:=/diff_drive_controller/cmd_vel -p stamped:=True
54+
```
55+
56+
## More Information
57+
58+
For more information, please visit [Navigation2 with GPS](https://docs.nav2.org/tutorials/docs/navigation2_with_gps.html).

config/dual_ekf_navsat_params.yaml

Lines changed: 127 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,127 @@
1+
# For parameter descriptions, please refer to the template parameter files for each node.
2+
3+
ekf_filter_node_odom:
4+
ros__parameters:
5+
frequency: 50.0 # Increased from 30.0 for better update rate
6+
two_d_mode: true # Recommended to use 2d mode for nav2 in mostly planar environments
7+
print_diagnostics: true
8+
debug: false
9+
publish_tf: true
10+
11+
map_frame: map
12+
odom_frame: odom
13+
base_link_frame: base_link # the frame id used by the turtlebot's diff drive plugin
14+
world_frame: odom
15+
16+
odom0: diff_drive_controller/odom
17+
odom0_config: [false, false, false,
18+
false, false, false,
19+
true, true, true,
20+
false, false, true,
21+
false, false, false]
22+
odom0_queue_size: 10
23+
odom0_differential: true # Changed from false to improve accuracy during turns
24+
odom0_relative: false
25+
26+
imu0: imu/data
27+
imu0_config: [false, false, false,
28+
false, false, true,
29+
true, true, true, # Added linear acceleration
30+
false, false, false,
31+
false, false, false]
32+
imu0_differential: true # If using a real robot you might want to set this to true, since usually absolute measurements from real imu's are not very accurate
33+
imu0_relative: false
34+
imu0_queue_size: 10
35+
imu0_remove_gravitational_acceleration: true
36+
37+
use_control: false
38+
39+
process_noise_covariance: [1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
40+
0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
41+
0.0, 0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
42+
0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
43+
0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
44+
0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
45+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
46+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
47+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
48+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0,
49+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0,
50+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0,
51+
0.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, 0.0, 0.0,
52+
0.0, 0.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, 0.0,
53+
0.0, 0.0, 0.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]
54+
55+
ekf_filter_node_map:
56+
ros__parameters:
57+
frequency: 50.0 # Increased from 30.0 for better update rate
58+
two_d_mode: true # Recommended to use 2d mode for nav2 in mostly planar environments
59+
print_diagnostics: true
60+
debug: false
61+
publish_tf: true
62+
63+
map_frame: map
64+
odom_frame: odom
65+
base_link_frame: base_link # the frame id used by the turtlebot's diff drive plugin
66+
world_frame: map
67+
68+
odom0: diff_drive_controller/odom
69+
odom0_config: [false, false, false,
70+
false, false, false,
71+
true, true, true,
72+
false, false, true,
73+
false, false, false]
74+
odom0_queue_size: 10
75+
odom0_differential: true # Changed from false to improve accuracy during turns
76+
odom0_relative: false
77+
78+
odom1: odometry/gps
79+
odom1_config: [true, true, false,
80+
false, false, false,
81+
false, false, false,
82+
false, false, false,
83+
false, false, false]
84+
odom1_queue_size: 10
85+
odom1_differential: false
86+
odom1_relative: false
87+
88+
imu0: imu/data
89+
imu0_config: [false, false, false,
90+
false, false, true,
91+
true, true, true, # Added linear acceleration
92+
false, false, false,
93+
false, false, false]
94+
imu0_differential: true # If using a real robot you might want to set this to true, since usually absolute measurements from real imu's are not very accurate
95+
imu0_relative: false
96+
imu0_queue_size: 10
97+
imu0_remove_gravitational_acceleration: true
98+
99+
use_control: false
100+
101+
process_noise_covariance: [1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
102+
0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
103+
0.0, 0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
104+
0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
105+
0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
106+
0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
107+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
108+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
109+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
110+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0,
111+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0,
112+
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0,
113+
0.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, 0.0, 0.0,
114+
0.0, 0.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, 0.0,
115+
0.0, 0.0, 0.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]
116+
117+
navsat_transform:
118+
ros__parameters:
119+
frequency: 50.0 # Increased from 30.0 for better update rate
120+
delay: 3.0
121+
magnetic_declination_radians: 0.0
122+
yaw_offset: 0.0
123+
zero_altitude: true
124+
broadcast_cartesian_transform: true
125+
publish_filtered_gps: true
126+
use_odometry_yaw: true
127+
wait_for_datum: false

config/gps_wpf_demo.mvc

Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
capture_directory: "~"
2+
fixed_frame: map
3+
target_frame: map
4+
fix_orientation: false
5+
rotate_90: false
6+
enable_antialiasing: true
7+
show_displays: true
8+
show_status_bar: true
9+
show_capture_tools: true
10+
view_scale: 0.564473748
11+
offset_x: -55.0469894
12+
offset_y: -4.65194941
13+
use_latest_transforms: true
14+
background: "#a0a0a4"
15+
image_transport: raw
16+
displays:
17+
- type: mapviz_plugins/tile_map
18+
name: new display
19+
config:
20+
visible: true
21+
collapsed: false
22+
custom_sources:
23+
- base_url: https://api.maptiler.com/tiles/satellite-v2/{level}/{x}/{y}.jpg?key=prOIJC29PpyOVqzLxuuJ
24+
max_zoom: 23
25+
name: mt
26+
type: wmts
27+
- base_url: http://tile.openstreetmap.org/{level}/{x}/{y}.png
28+
max_zoom: 21
29+
name: osm
30+
type: wmts
31+
bing_api_key: ""
32+
source: mt
33+
- type: mapviz_plugins/point_click_publisher
34+
name: new display
35+
config:
36+
visible: true
37+
collapsed: false
38+
topic: clicked_point
39+
output_frame: wgs84
40+
- type: mapviz_plugins/tf_frame
41+
name: new display
42+
config:
43+
visible: true
44+
collapsed: false
45+
frame: base_link
46+
color: "#00ff00"
47+
draw_style: arrows
48+
position_tolerance: 0
49+
buffer_size: 1
50+
static_arrow_sizes: true
51+
arrow_size: 53
52+
- type: mapviz_plugins/navsat
53+
name: new display
54+
config:
55+
visible: true
56+
collapsed: false
57+
topic: /gps/fix
58+
color: "#55aaff"
59+
draw_style: points
60+
position_tolerance: 0
61+
buffer_size: 1

config/my_controllers.yaml

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,10 @@ controller_manager:
55
joint_state_broadcaster:
66
type: joint_state_broadcaster/JointStateBroadcaster
77

8-
diff_drive_base_controller:
8+
diff_drive_controller:
99
type: diff_drive_controller/DiffDriveController
1010

11-
diff_drive_base_controller:
11+
diff_drive_controller:
1212
ros__parameters:
1313
left_wheel_names: ["front_left_wheel_joint", "rear_left_wheel_joint"]
1414
right_wheel_names: ["front_right_wheel_joint", "rear_right_wheel_joint"]
@@ -17,6 +17,7 @@ diff_drive_base_controller:
1717
wheel_radius: 0.033
1818

1919
publish_rate: 50.0
20-
# odom_frame_id: odom
20+
odom_frame_id: odom
2121
base_frame_id: base_link
22-
use_stamped_vel: false
22+
tf_frame_prefix_enable: false
23+
# open_loop: true

0 commit comments

Comments
 (0)