Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.8)
project(apricotka-robot-car)
project(ros_sw)

# Default to C99
if(NOT CMAKE_C_STANDARD)
Expand Down
58 changes: 58 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
# ROS Setup Instructions

## Install Required Packages

```bash
sudo apt install ros-jazzy-navigation2
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These packages should be in package.xml and installed with rosdep.

sudo apt install ros-jazzy-nav2-bringup
sudo apt install ros-jazzy-robot-localization
sudo apt install ros-jazzy-mapviz
sudo apt install ros-jazzy-mapviz-plugins
sudo apt install ros-jazzy-tile-map
```

## Setup ROS Environment

```bash
source /opt/ros/jazzy/setup.bash
```

## Create Workspace and Clone Repositories

```bash
mkdir gps_ws
cd gps_ws
git clone -b 10-gps-navigation https://github.com/KPI-Rover/ros_sw.git
git clone -b jazzy https://github.com/ros-navigation/navigation2_tutorials.git
```

## Build the Workspace

```bash
colcon build --symlink-install
source install/setup.bash
```

## Launch Simulation

```bash
ros2 launch ros_sw launch_sim.launch.py use_rviz:=True use_mapviz:=True
```

## Run GPS Waypoint Follower Demos

```bash
ros2 run nav2_gps_waypoint_follower_demo interactive_waypoint_follower
ros2 run nav2_gps_waypoint_follower_demo gps_waypoint_logger </path/to/yaml/file.yaml>
ros2 run nav2_gps_waypoint_follower_demo logged_waypoint_follower </path/to/yaml/file.yaml>
```

## Run Teleop Twist Keyboard

```bash
ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args -r /cmd_vel:=/diff_drive_controller/cmd_vel -p stamped:=True
```

## More Information

For more information, please visit [Navigation2 with GPS](https://docs.nav2.org/tutorials/docs/navigation2_with_gps.html).
127 changes: 127 additions & 0 deletions config/dual_ekf_navsat_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,127 @@
# For parameter descriptions, please refer to the template parameter files for each node.

ekf_filter_node_odom:
ros__parameters:
frequency: 50.0 # Increased from 30.0 for better update rate
two_d_mode: true # Recommended to use 2d mode for nav2 in mostly planar environments
print_diagnostics: true
debug: false
publish_tf: true

map_frame: map
odom_frame: odom
base_link_frame: base_link # the frame id used by the turtlebot's diff drive plugin
world_frame: odom

odom0: diff_drive_controller/odom
odom0_config: [false, false, false,
false, false, false,
true, true, true,
false, false, true,
false, false, false]
odom0_queue_size: 10
odom0_differential: true # Changed from false to improve accuracy during turns
odom0_relative: false

imu0: imu/data
imu0_config: [false, false, false,
false, false, true,
true, true, true, # Added linear acceleration
false, false, false,
false, false, false]
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
imu0_relative: false
imu0_queue_size: 10
imu0_remove_gravitational_acceleration: true

use_control: false

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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
0.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,
0.0, 0.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, 0.0, 0.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]

ekf_filter_node_map:
ros__parameters:
frequency: 50.0 # Increased from 30.0 for better update rate
two_d_mode: true # Recommended to use 2d mode for nav2 in mostly planar environments
print_diagnostics: true
debug: false
publish_tf: true

map_frame: map
odom_frame: odom
base_link_frame: base_link # the frame id used by the turtlebot's diff drive plugin
world_frame: map

odom0: diff_drive_controller/odom
odom0_config: [false, false, false,
false, false, false,
true, true, true,
false, false, true,
false, false, false]
odom0_queue_size: 10
odom0_differential: true # Changed from false to improve accuracy during turns
odom0_relative: false

odom1: odometry/gps
odom1_config: [true, true, false,
false, false, false,
false, false, false,
false, false, false,
false, false, false]
odom1_queue_size: 10
odom1_differential: false
odom1_relative: false

imu0: imu/data
imu0_config: [false, false, false,
false, false, true,
true, true, true, # Added linear acceleration
false, false, false,
false, false, false]
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
imu0_relative: false
imu0_queue_size: 10
imu0_remove_gravitational_acceleration: true

use_control: false

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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
0.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,
0.0, 0.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, 0.0, 0.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]

navsat_transform:
ros__parameters:
frequency: 50.0 # Increased from 30.0 for better update rate
delay: 3.0
magnetic_declination_radians: 0.0
yaw_offset: 0.0
zero_altitude: true
broadcast_cartesian_transform: true
publish_filtered_gps: true
use_odometry_yaw: true
wait_for_datum: false
61 changes: 61 additions & 0 deletions config/gps_wpf_demo.mvc
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
capture_directory: "~"
fixed_frame: map
target_frame: map
fix_orientation: false
rotate_90: false
enable_antialiasing: true
show_displays: true
show_status_bar: true
show_capture_tools: true
view_scale: 0.564473748
offset_x: -55.0469894
offset_y: -4.65194941
use_latest_transforms: true
background: "#a0a0a4"
image_transport: raw
displays:
- type: mapviz_plugins/tile_map
name: new display
config:
visible: true
collapsed: false
custom_sources:
- base_url: https://api.maptiler.com/tiles/satellite-v2/{level}/{x}/{y}.jpg?key=prOIJC29PpyOVqzLxuuJ
max_zoom: 23
name: mt
type: wmts
- base_url: http://tile.openstreetmap.org/{level}/{x}/{y}.png
max_zoom: 21
name: osm
type: wmts
bing_api_key: ""
source: mt
- type: mapviz_plugins/point_click_publisher
name: new display
config:
visible: true
collapsed: false
topic: clicked_point
output_frame: wgs84
- type: mapviz_plugins/tf_frame
name: new display
config:
visible: true
collapsed: false
frame: base_link
color: "#00ff00"
draw_style: arrows
position_tolerance: 0
buffer_size: 1
static_arrow_sizes: true
arrow_size: 53
- type: mapviz_plugins/navsat
name: new display
config:
visible: true
collapsed: false
topic: /gps/fix
color: "#55aaff"
draw_style: points
position_tolerance: 0
buffer_size: 1
9 changes: 5 additions & 4 deletions config/my_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,10 @@ controller_manager:
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

diff_drive_base_controller:
diff_drive_controller:
type: diff_drive_controller/DiffDriveController

diff_drive_base_controller:
diff_drive_controller:
ros__parameters:
left_wheel_names: ["front_left_wheel_joint", "rear_left_wheel_joint"]
right_wheel_names: ["front_right_wheel_joint", "rear_right_wheel_joint"]
Expand All @@ -17,6 +17,7 @@ diff_drive_base_controller:
wheel_radius: 0.033

publish_rate: 50.0
# odom_frame_id: odom
odom_frame_id: odom
base_frame_id: base_link
use_stamped_vel: false
tf_frame_prefix_enable: false
# open_loop: true
Loading