Skip to content
This repository has been archived by the owner on Nov 16, 2023. It is now read-only.

Commit

Permalink
feat(#215): more cleanup, change to leaderboard and small fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
vogelnik committed Mar 21, 2023
1 parent d87d3bf commit 00aedd2
Show file tree
Hide file tree
Showing 10 changed files with 17 additions and 26 deletions.
2 changes: 1 addition & 1 deletion build/Taskfile
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ task:shell() {
##########################################
task:install() {
task:install:git_hooks
task:gitconfig:copy
#task:gitconfig:copy
install:gpu-support
docker:install
}
Expand Down
4 changes: 2 additions & 2 deletions build/docker-compose.yml
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ services:
tty: true
shm_size: 2gb
#command: bash -c "sleep 10 && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/opt/leaderboard/leaderboard/autoagents/npc_agent.py --host=carla-simulator --track=SENSORS"
command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch"
#command: bash -c "sleep 10 && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP"
#command: bash -c "sleep 10 && roslaunch agent/launch/dev.launch"
command: bash -c "sleep 10 && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=/opt/leaderboard/data/routes_devtest.xml --agent=/workspace/code/agent/src/agent/agent.py --host=carla-simulator --track=MAP"
logging:
driver: "local"
environment:
Expand Down
8 changes: 1 addition & 7 deletions code/acting/src/acting/pure_pursuit_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
from nav_msgs.msg import Path
from ros_compatibility.node import CompatibleNode
from rospy import Publisher, Subscriber
from std_msgs.msg import Float32, Float32MultiArray
from std_msgs.msg import Float32
from acting.msg import Debug

from helper_functions import vector_angle
Expand Down Expand Up @@ -65,18 +65,12 @@ def __init__(self):
f"/paf/{self.role_name}/debug",
qos_profile=1)

self.max_speed_pub: Publisher = self.new_publisher(
Float32,
f"/paf/{self.role_name}/speed_limit",
qos_profile=1)

self.__position: (float, float) = None # x, y
self.__last_pos: (float, float) = None
self.__path: Path = None
self.__heading: float = None
self.__velocity: float = None
self.__tp_idx: int = 0 # target waypoint index
self.__od_speed: Float32MultiArray = None
# error when there are no targets

def run(self):
Expand Down
8 changes: 1 addition & 7 deletions code/acting/src/acting/stanley_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
# from ros_compatibility.qos import QoSProfile, DurabilityPolicy
from rospy import Publisher, Subscriber
# from sensor_msgs.msg import NavSatFix, Imu
from std_msgs.msg import Float32, Float32MultiArray # Bool
from std_msgs.msg import Float32 # Bool
from acting.msg import StanleyDebug

from helper_functions import vector_angle
Expand Down Expand Up @@ -62,18 +62,12 @@ def __init__(self):
f"/paf/{self.role_name}/stanley_debug",
qos_profile=1)

self.max_speed_pub: Publisher = self.new_publisher(
Float32,
f"/paf/{self.role_name}/speed_limit",
qos_profile=1)

self.__position: (float, float) = None # x, y
self.__last_pos: (float, float) = None
self.__path: Path = None
self.__heading: float = None
self.__velocity: float = None
self.__tp_idx: int = 0 # target waypoint index
self.__od_speed: Float32MultiArray = None
# error when there are no targets

def run(self):
Expand Down
4 changes: 2 additions & 2 deletions code/acting/src/acting/vehicle_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ def __init__(self):
self.__velocity: float = 0.0
self.__pure_pursuit_steer: float = 0.0
self.__stanley_steer: float = 0.0
self.__current_steer: float = 0.0 # check emergency behaviour
self.__current_steer: float = 0.0 # todo: check emergency behaviour

def run(self):
"""
Expand All @@ -107,7 +107,7 @@ def run(self):
"""
self.status_pub.publish(True)
self.loginfo('VehicleController node running')
pid = PID(0.85, 0.1, 0.1, setpoint=0) # random values -> tune
pid = PID(0.85, 0.1, 0.1, setpoint=0) # random values -> todo: tune
pid.output_limits = (-MAX_STEER_ANGLE, MAX_STEER_ANGLE)

def loop(timer_event=None) -> None:
Expand Down
4 changes: 1 addition & 3 deletions code/acting/src/acting/velocity_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
from nav_msgs.msg import Path

# TODO put back to 36 when controller can handle it
SPEED_LIMIT_DEFAULT: float = 8 # 36.0
SPEED_LIMIT_DEFAULT: float = 6 # 36.0


class VelocityController(CompatibleNode):
Expand Down Expand Up @@ -142,8 +142,6 @@ def loop(timer_event=None):
self.logerr("Velocity controller doesn't support backward "
"driving yet.")
return
# print(f"v_soll = min({self.__max_velocity}, {self.__max_tree_v},
# {self.__speed_limit}) | v_ist = {self.__current_velocity} ")
v = min(self.__max_velocity, self.__max_tree_v)
v = min(v, self.__speed_limit)

Expand Down
2 changes: 1 addition & 1 deletion code/agent/config/dev_objects.json
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
"id": "hero",
"role_name": "hero",
"spawn_point": {
"x": 986.0,
"x": 984.5,
"y": -5442.0,
"z": 371.0,
"yaw": -90.0,
Expand Down
4 changes: 2 additions & 2 deletions code/agent/src/agent/agent.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,15 @@ def sensors(self):
'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100},
{'type': 'sensor.lidar.ray_cast', 'id': 'LIDAR',
'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,
'yaw': -45.0},
'yaw': 0.0},
{'type': 'sensor.other.radar', 'id': 'RADAR',
'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,
'yaw': -45.0, 'horizontal_fov': 30, 'vertical_fov': 30},
{'type': 'sensor.other.gnss', 'id': 'GPS',
'x': 0.7, 'y': -0.4, 'z': 1.60},
{'type': 'sensor.other.imu', 'id': 'IMU',
'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0,
'yaw': -45.0},
'yaw': 0.0},
{'type': 'sensor.opendrive_map', 'id': 'OpenDRIVE',
'reading_frequency': 1},
{'type': 'sensor.speedometer', 'id': 'Speed'},
Expand Down
4 changes: 4 additions & 0 deletions code/perception/src/global_plan_distance_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,10 @@ def distance(a, b):
if current_distance < 2.5 or next_distance < current_distance:
self.road_options.pop(0)
self.global_route.pop(0)
if self.road_options[0] in {5, 6} and \
self.road_options[0] == self.road_options[1]:
self.road_options.pop(0)
self.global_route.pop(0)
print(f"next road option = {self.road_options[0]}")

def update_global_route(self, route):
Expand Down
3 changes: 2 additions & 1 deletion code/planning/global_planner/launch/global_planner.launch
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
<launch>
<!--
<node pkg="planning" type="dev_global_route.py" name="DevGlobalRoute" output="screen">
<param name="from_txt" value="True" />
<param name="sampling_resolution" value="75.0" />
<param name="routes" value="/opt/leaderboard/data/routes_devtest.xml" />
<param name="global_route_txt" value="/code/planning/global_planner/src/global_route.txt" />
<param name="role_name" value="hero" />
</node>
</node>-->
<node pkg="planning" type="preplanner.py" name="PrePlanner" output="screen">
<param name="role_name" value="hero" />
<param name="control_loop_rate" value="1" />
Expand Down

0 comments on commit 00aedd2

Please sign in to comment.