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

Commit

Permalink
feat(#167): removed IMU as an EKF input
Browse files Browse the repository at this point in the history
  • Loading branch information
schwalga committed Jan 29, 2023
1 parent 58d0cff commit 4958475
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 12 deletions.
2 changes: 1 addition & 1 deletion code/acting/src/acting/vehicle_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ def loop(timer_event=None) -> None:

message.hand_brake = False
message.manual_gear_shift = False
message.steer = steer
message.steer = steer + 0.125 # todo: remove + 0.125
message.gear = 1
message.header.stamp = roscomp.ros_timestamp(self.get_time(),
from_sec=True)
Expand Down
6 changes: 3 additions & 3 deletions code/acting/src/acting/velocity_publisher_dummy.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@ def __init__(self):
Float32,
f"/carla/{self.role_name}/max_velocity",
qos_profile=1)
self.velocity = 7
self.delta_velocity = 0.25
self.max_velocity = 10
self.velocity = 5
self.delta_velocity = 0
self.max_velocity = 5
self.min_velocity = 5
self.__dv = self.delta_velocity

Expand Down
6 changes: 3 additions & 3 deletions code/agent/config/dev_objects.json
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,9 @@
"role_name": "hero",
"spawn_point": {
"x": 983.5,
"y": -5373.2,
"z": 371.5,
"yaw": -90.0,
"y": -5893.2,
"z": 368.0,
"yaw": 0.0,
"pitch": 0.0,
"roll": 0.0
},
Expand Down
6 changes: 3 additions & 3 deletions code/perception/launch/perception.launch
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,9 @@
<param name="freq" value="20.0"/>
<param name="sensor_timeout" value="10.0"/>
<param name="odom_used" value="false"/>
<param name="imu_used" value="true"/>
<param name="imu_used" value="false"/>
<param name="vo_used" value="true"/>
<param name="debug" value="true"/>
<param name="self_diagnose" value="true"/>
<param name="debug" value="false"/>
<param name="self_diagnose" value="false"/>
</node>
</launch>
7 changes: 5 additions & 2 deletions code/perception/src/EKFTranslationNode.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
from coordinate_transformation import CoordinateTransformer, GeoRef


GPS_RUNNING_AVG_ARGS = 3 # points taken into account for the avg
GPS_RUNNING_AVG_ARGS = 5 # points taken into account for the avg


class EKFTranslation(CompatibleNode):
Expand Down Expand Up @@ -66,6 +66,7 @@ def __init__(self):
qos_profile=1)

self.avg_xyz = np.zeros((GPS_RUNNING_AVG_ARGS, 3))
self.__publish_counter: int = 0
# 3D Odometry (GPS)
self.ekf_vo_publisher = self.new_publisher(
Odometry,
Expand Down Expand Up @@ -142,7 +143,9 @@ def update_gps_data(self, data: NavSatFix):
0, 0, 0, 0, 999999, 0,
0, 0, 0, 0, 0, 999999]

self.ekf_vo_publisher.publish(odom_msg)
self.__publish_counter += 1
if self.__publish_counter % 5 == 0:
self.ekf_vo_publisher.publish(odom_msg)

def run(self):
"""
Expand Down

0 comments on commit 4958475

Please sign in to comment.