Skip to content

Commit 3333587

Browse files
authored
Merge pull request #2 from Kim-mins/updated_version
fix: Fix issues on control & perception and improvement on handling control message.
2 parents 9a57ef4 + f66488a commit 3333587

File tree

5 files changed

+20
-47
lines changed

5 files changed

+20
-47
lines changed

simulator/carla_autoware/README.md

-2
Original file line numberDiff line numberDiff line change
@@ -137,5 +137,3 @@ The `carla_ros.py` sets up the CARLA world:
137137
- Sensor currently not automatically configurated to have the same location as the Autoware Sensor kit. The current work around is to create a new frame of each sensors with (0, 0, 0, 0, 0, 0) coordinate relative to base_link and attach each sensor on the new frame (`carla_autoware.launch.xml` Line 28). This work around is very limited and restrictive, as when the sensor_kit is changed the sensor location will be wrongly attached.
138138
- Traffic light recognition.
139139
- Currently the HDmap of CARLA did not have information regarding the traffic light which is necessary for Autoware to conduct traffic light recognition.
140-
- Ego Vehicle Control.
141-
- Currently during sharp turning the ego-vehicle have large lateral error.

simulator/carla_autoware/config/objects.json

+8-8
Original file line numberDiff line numberDiff line change
@@ -21,17 +21,17 @@
2121
"spawn_point": {
2222
"x": 0.0,
2323
"y": 0.0,
24-
"z": 2.6,
24+
"z": 3.1,
2525
"roll": 0.0,
2626
"pitch": 0.0,
2727
"yaw": 0.0
2828
},
29-
"range": 20,
30-
"channels": 32,
31-
"points_per_second": 200000,
32-
"upper_fov": 3.0,
33-
"lower_fov": -27.0,
34-
"rotation_frequency": 20,
29+
"range": 100,
30+
"channels": 64,
31+
"points_per_second": 1200000,
32+
"upper_fov": 10.0,
33+
"lower_fov": -30.0,
34+
"rotation_frequency": 50,
3535
"noise_stddev": 0.0
3636
},
3737
{
@@ -59,4 +59,4 @@
5959
}
6060
}
6161
]
62-
}
62+
}

simulator/carla_autoware/src/carla_autoware/carla_autoware.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ def _tick_sensor(self, timestamp):
4848
ego_action = self.sensor()
4949
except SensorReceivedNoData as e:
5050
raise RuntimeError(e)
51-
self.ego_vehicle.apply_control(ego_action)
51+
self.ego_vehicle.apply_ackermann_control(ego_action)
5252
if self.running:
5353
CarlaDataProvider.get_world().tick()
5454

simulator/carla_autoware/src/carla_autoware/carla_ros.py

+11-23
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,6 @@
4646
from .modules.carla_utils import carla_rotation_to_ros_quaternion
4747
from .modules.carla_utils import create_cloud
4848
from .modules.carla_utils import ros_pose_to_carla_transform
49-
from .modules.carla_utils import steer_to_angle_map
5049
from .modules.carla_wrapper import SensorInterface
5150

5251

@@ -119,7 +118,7 @@ def setup(self):
119118
PoseWithCovarianceStamped, "initialpose", self.initialpose_callback, 1
120119
)
121120

122-
self.current_control = carla.VehicleControl()
121+
self.current_control = carla.VehicleAckermannControl()
123122

124123
# Direct data publishing from CARLA for Autoware
125124
self.pub_pose_with_cov = self.ros2_node.create_publisher(
@@ -378,23 +377,13 @@ def imu(self, carla_imu_measurement):
378377

379378
def control_callback(self, in_cmd):
380379
"""Convert and publish CARLA Ego Vehicle Control to AUTOWARE."""
381-
out_cmd = carla.VehicleControl()
382-
self.target_vel = in_cmd.longitudinal.speed
383-
self.vel_diff = self.target_vel - self.current_vel
384-
385-
if self.vel_diff > 0:
386-
out_cmd.throttle = 0.75
387-
out_cmd.brake = 0.0
388-
elif self.vel_diff <= 0.0:
389-
out_cmd.throttle = 0.0
390-
if self.target_vel <= 0.0:
391-
out_cmd.brake = 0.75
392-
elif self.vel_diff > -1:
393-
out_cmd.brake = 0.0
394-
else:
395-
out_cmd.brake = 0.01
396-
397-
out_cmd.steer = -in_cmd.lateral.steering_tire_angle
380+
out_cmd = carla.VehicleAckermannControl(
381+
steer=numpy.clip(-math.degrees(in_cmd.lateral.steering_tire_angle)/self.max_steering_angle, -1.0, 1.0),
382+
steer_speed=in_cmd.lateral.steering_tire_rotation_rate,
383+
speed=in_cmd.longitudinal.speed,
384+
acceleration=in_cmd.longitudinal.acceleration,
385+
jerk=in_cmd.longitudinal.jerk
386+
)
398387
self.current_control = out_cmd
399388

400389
def ego_status(self):
@@ -406,7 +395,6 @@ def ego_status(self):
406395
self.param_values["ego_vehicle_role_name"]
407396
)
408397

409-
in_status = ego_vehicle.get_control()
410398
self.current_vel = CarlaDataProvider.get_velocity(
411399
CarlaDataProvider.get_actor_by_name(self.param_values["ego_vehicle_role_name"])
412400
)
@@ -423,10 +411,10 @@ def ego_status(self):
423411
out_vel_state.heading_rate = 0.0
424412

425413
out_steering_state.stamp = out_vel_state.header.stamp
426-
out_steering_state.steering_tire_angle = steer_to_angle_map(self.max_steering_angle)(
427-
in_status.steer
414+
out_steering_state.steering_tire_angle = -math.radians(
415+
ego_vehicle.get_wheel_steer_angle(carla.VehicleWheelLocation.FL_Wheel)
428416
)
429-
417+
430418
out_gear_state.stamp = out_vel_state.header.stamp
431419
out_gear_state.report = GearReport.DRIVE
432420

simulator/carla_autoware/src/carla_autoware/modules/carla_utils.py

-13
Original file line numberDiff line numberDiff line change
@@ -108,16 +108,3 @@ def ros_pose_to_carla_transform(ros_pose):
108108
carla.Location(ros_pose.position.x, -ros_pose.position.y, ros_pose.position.z),
109109
ros_quaternion_to_carla_rotation(ros_pose.orientation),
110110
)
111-
112-
113-
def steer_to_angle_map(max_steering_angle):
114-
"""Compute the mapping from steering values to corresponding angles."""
115-
left_steer = -1
116-
right_steer = 1
117-
left_angle = np.radians(-max_steering_angle)
118-
right_angle = -left_angle
119-
steer_values = [left_steer, right_steer]
120-
angle_values = [left_angle, right_angle]
121-
coefficients = np.polyfit(steer_values, angle_values, 1)
122-
mapping_function = np.poly1d(coefficients)
123-
return mapping_function

0 commit comments

Comments
 (0)