Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Auton overtake feature, as well as pylint fixes #39

Merged
merged 12 commits into from
Feb 14, 2024
10 changes: 10 additions & 0 deletions .github/workflows/.pylintrc
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
[MESSAGES CONTROL]

disable=all

enable=
bad-indentation,
trailing-whitespace,
wrong-import-order,
unused-variable,
unused-import
35 changes: 35 additions & 0 deletions .github/workflows/pylint.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
name: Pylint

on: [push]

jobs:
build:
runs-on: ubuntu-latest
strategy:
matrix:
python-version: ["3.8", "3.9", "3.10"]
steps:
- uses: actions/checkout@v3
- name: Set up Python ${{ matrix.python-version }}
uses: actions/setup-python@v3
with:
python-version: ${{ matrix.python-version }}
- name: Install dependencies
run: |
python -m pip install --upgrade pip
pip install pylint
- name: Getting changed Python files and Analysing the code with pylint
run: |
git fetch origin ${CI_MERGE_REQUEST_TARGET_BRANCH_NAME}
echo CI_COMMIT_SHA=${GITHUB_SHA}
tmp_files=$(git diff --name-only origin/main ${CI_COMMIT_SHA})
echo "Changed files are $tmp_files"
if [ -z "$(echo "$tmp_files" | grep "\.py")" ]; then exit 0; else echo "Python files are found"; fi
tmp_pfiles=$(echo "$tmp_files" | grep "\.py")
echo "Python files are $tmp_pfiles"
if [[ -z "$tmp_pfiles" ]]; then
echo "No files to lint"
else
echo "Running Linter!"
pylint --rc-file=/home/runner/work/RoboBuggy2/RoboBuggy2/.github/workflows/.pylintrc $tmp_pfiles
fi
Empty file modified rb_ws/src/buggy/launch/main.launch
100644 → 100755
Empty file.
34 changes: 18 additions & 16 deletions rb_ws/src/buggy/launch/sim_2d_2buggies.launch
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -3,34 +3,36 @@
<!-- <arg name="name" value="INS" /> -->

<launch>
<arg name="sc_controller" default="stanley" />
<arg name="sc_start_dist" default="0.0" />
<arg name="sc_path" default="buggycourse_safe_1.json" />
<arg name="sc_starting_pose" default="Hill1_SC" />
<arg name="sc_velocity" default="15.0" />

<arg name="nand_controller" default="stanley" />
<arg name="nand_start_dist" default="30.0" />
<arg name="nand_path" default="buggycourse_safe_1.json" />

<arg name="nand_starting_pose" default="Hill1_NAND" />
<arg name="nand_velocity" default="12.0" />
<arg name="nand_velocity" default="10.0" />


<node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />
<node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />

<node name="nand_sim_2d_engine" pkg="buggy" type="engine.py" output="screen"
args="$(arg nand_starting_pose) $(arg nand_velocity) NAND"/>
<!-- <node name="nand_vel_updater" pkg="buggy" type="velocity_updater.py"
output="screen" args="$(arg nand_velocity) NAND"/> -->

<!-- NAND is not aware of SC -->
<arg name="nand_autonsystem_args" default="--controller stanley --dist 0.0 --traj buggycourse_safe_1.json --self_name NAND" />
<node name="nand_auton_system" pkg="buggy" type="autonsystem.py" output="screen"
args="$(arg nand_autonsystem_args)"/>

<node name="sc_sim_2d_engine" pkg="buggy" type="engine.py" output="screen"
args="$(arg sc_starting_pose) $(arg sc_velocity) SC"/>
<node name="sc_vel_updater" pkg="buggy" type="velocity_updater.py"
output="screen" args="$(arg sc_velocity) SC"/>
<!-- <node name="sc_vel_updater" pkg="buggy" type="velocity_updater.py"
output="screen" args="$(arg sc_velocity) SC"/> -->

<!-- autonsystem args: controller start_dist path buggy_name is_sim -->
<arg name="sc_autonsystem_args" default="--controller stanley --dist 0.0 --traj buggycourse_safe_1.json --self_name SC --other_name NAND" />
<node name="sc_auton_system" pkg="buggy" type="autonsystem.py" output="screen"
args="$(arg sc_controller) $(arg sc_start_dist) $(arg sc_path) SC True"/>
args="$(arg sc_autonsystem_args)"/>

<node name="nand_sim_2d_engine" pkg="buggy" type="engine.py" output="screen"
args="$(arg nand_starting_pose) $(arg nand_velocity) Nand"/>
<node name="nand_vel_updater" pkg="buggy" type="velocity_updater.py"
output="screen" args="$(arg nand_velocity) Nand"/>

<node name="nand_auton_system" pkg="buggy" type="autonsystem.py" output="screen"
args="$(arg nand_controller) $(arg nand_start_dist) $(arg nand_path) Nand True"/>
</launch>
17 changes: 8 additions & 9 deletions rb_ws/src/buggy/launch/sim_2d_single.launch
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -3,21 +3,20 @@
<!-- <arg name="name" value="INS" /> -->

<launch>
<arg name="buggy_name" default="SC" />
<arg name="controller" default="stanley" />
<arg name="start_dist" default="0.0" />
<arg name="path" default="buggycourse_safe_1.json" />
<arg name="autonsystem_args" default="--controller stanley --dist 0.0 --traj buggycourse_safe_1.json --self_name SC" />
<arg name="starting_pose" default="Hill1_SC" />
<arg name="velocity" default="15.0" />

<arg name="buggy_name" default="SC" />

<node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />

<node name="sim_2d_engine" pkg="buggy" type="engine.py" output="screen"
args="$(arg starting_pose) $(arg velocity) $(arg buggy_name)"/>
<node name="vel_updater" pkg="buggy" type="velocity_updater.py"
output="screen" args="$(arg velocity) $(arg buggy_name)"/>
<!-- autonsystem args: controller start_dist path buggy_name is_sim -->

<!-- <node name="vel_updater" pkg="buggy" type="velocity_updater.py"
output="screen" args="$(arg velocity) $(arg buggy_name)"/> -->

<node name="auton_system" pkg="buggy" type="autonsystem.py" output="screen"
args="$(arg controller) $(arg start_dist) $(arg path) $(arg buggy_name) True"/>
args="$(arg autonsystem_args)"/>

</launch>
29 changes: 16 additions & 13 deletions rb_ws/src/buggy/scripts/2d_sim/engine.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,16 @@
#! /usr/bin/env python3

import sys
import threading

import rospy
from geometry_msgs.msg import Pose, Twist, PoseWithCovariance, TwistWithCovariance
from std_msgs.msg import Float64
from sensor_msgs.msg import NavSatFix
from nav_msgs.msg import Odometry
import threading
import numpy as np
import utm
import time
import sys



class Simulator:
Expand Down Expand Up @@ -45,15 +47,16 @@ def __init__(self, starting_pose, velocity, buggy_name):
buggy_name + "/state/pose_navsat", NavSatFix, queue_size=1
)

# to plot on Foxglove (with noise)
self.navsatfix_noisy_publisher = rospy.Publisher(
buggy_name + "/state/pose_navsat_noisy", NavSatFix, queue_size=1
)
if Simulator.NOISE:
# to plot on Foxglove (with noise)
self.navsatfix_noisy_publisher = rospy.Publisher(
buggy_name + "/state/pose_navsat_noisy", NavSatFix, queue_size=1
)

# (UTM east, UTM north, HEADING(degs))
self.starting_poses = {
"Hill1_SC": (Simulator.UTM_EAST_ZERO + 60, Simulator.UTM_NORTH_ZERO + 150, -110),
"Hill1_NAND": (Simulator.UTM_EAST_ZERO + 55, Simulator.UTM_NORTH_ZERO + 165, -125),
"Hill1_NAND": (Simulator.UTM_EAST_ZERO + 0, Simulator.UTM_NORTH_ZERO + 0, -110),
"Hill1_SC": (Simulator.UTM_EAST_ZERO + 20, Simulator.UTM_NORTH_ZERO + 30, -110),
}

# Start position for End of Hill 2
Expand All @@ -69,12 +72,12 @@ def __init__(self, starting_pose, velocity, buggy_name):
# self.e_utm = utm_coords[0]
# self.n_utm = utm_coords[1]

self.e_utm, self.n_utm, self.heading = self.starting_poses[starting_pose]
self.e_utm, self.n_utm, self.heading = self.starting_poses[starting_pose]
self.velocity = velocity # m/s

self.steering_angle = 0 # degrees
self.rate = 100 # Hz
self.pub_skip = 10 # publish every pub_skip ticks
self.rate = 200 # Hz
self.pub_skip = 1 # publish every pub_skip ticks

self.lock = threading.Lock()

Expand Down Expand Up @@ -121,7 +124,7 @@ def dynamics(self, state, v):
dstate (np.Array): time derivative of state from dynamics
"""
l = Simulator.WHEELBASE
x, y, theta, delta = state
_, _, theta, delta = state

return np.array([v * np.cos(theta),
v * np.sin(theta),
Expand Down
Loading
Loading