Skip to content

Commit c498a4b

Browse files
authored
Merge pull request #14 from wheelos/update_1
update
2 parents 0699d61 + c17d4d5 commit c498a4b

File tree

89 files changed

+5002
-123
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

89 files changed

+5002
-123
lines changed

MODULE.bazel

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,18 @@ bazel_dep(name = "cpplint", version = "2.0.2")
4444
bazel_dep(name = "eigen", version = "4.0.0-20241125.bcr.2")
4545
bazel_dep(name = "nlohmann_json", version = "3.12.0", repo_name = "com_github_nlohmann_json")
4646
bazel_dep(name = "gflags", version = "2.2.2", repo_name = "com_github_gflags_gflags")
47+
# Note: build gflags as a shared library and make the third-party(pre-compiled
48+
# library such as paddleinference) link to it to keep only one copy of gflags
49+
# in one process
50+
single_version_override(
51+
module_name = "gflags",
52+
patch_strip = 1,
53+
patches = [
54+
"//third_party/gflags:gflags-2.2.2-shared-library.patch",
55+
],
56+
version = "2.2.2",
57+
)
58+
4759
bazel_dep(name = "glog", version = "0.7.1", repo_name = "com_github_google_glog")
4860
single_version_override(
4961
module_name = "glog",

docker/scripts/dev_start.sh

Lines changed: 8 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,6 @@ DOCKER_MEMORY="${DOCKER_MEMORY:-8g}"
6666
# Default development image versions based on architecture and distribution
6767
# can be overridden by environment variables.
6868
DOCKER_IMAGE_REPO=${DOCKER_IMAGE_REPO:="wheelos/apollo"}
69-
WHL_DOCKER_IMAGE_REPO=${WHL_DOCKER_IMAGE_REPO:="wheelos"}
7069
DOCKER_IMAGE_TAG_X86_64=${DOCKER_IMAGE_TAG_X86_64:="dev-x86_64-20.04-20250713_1555"}
7170
DOCKER_IMAGE_TAG_X86_64_TESTING=${DOCKER_IMAGE_TAG_X86_64_TESTING:="dev-x86_64-20.04-20250710_2109"}
7271
DOCKER_IMAGE_TAG_AARCH64=${DOCKER_IMAGE_TAG_AARCH64:="dev-aarch64-20.04-20250714_2123"}
@@ -254,11 +253,7 @@ function determine_dev_image() {
254253
esac
255254
fi
256255
257-
if [[ "${CUSTOM_DIST}" == "testing" ]]; then
258-
DEV_IMAGE="${WHL_DOCKER_IMAGE_REPO}/${version}"
259-
else
260-
DEV_IMAGE="${DOCKER_IMAGE_REPO}:${version}"
261-
fi
256+
DEV_IMAGE="${DOCKER_IMAGE_REPO}:${version}"
262257
263258
info "Determined development image: ${DEV_IMAGE}"
264259
}
@@ -395,13 +390,15 @@ function docker_pull() {
395390
local base_image_name="$1"
396391
local __final_image_var_name="$2"
397392
393+
local base_image_repo="${base_image_name}"
394+
if [[ "$(image_contains_registry "${base_image_name}")" == "1" ]]; then
395+
base_image_repo="$(echo "${base_image_name}" | cut -d'/' -f2-)"
396+
fi
398397
local pull_candidate_image_name=""
399-
if [[ "${CUSTOM_DIST}" == "testing" && "${TARGET_ARCH}" == "x86_64" ]]; then
400-
pull_candidate_image_name="registry.cn-hangzhou.aliyuncs.com/${base_image_name}"
401-
elif [[ -v GEO_REGISTRY && -n "${GEO_REGISTRY}" ]]; then
402-
pull_candidate_image_name="${GEO_REGISTRY}/${base_image_name}"
398+
if [[ -v GEO_REGISTRY && -n "${GEO_REGISTRY}" ]]; then
399+
pull_candidate_image_name="${GEO_REGISTRY}/${base_image_repo}"
403400
else
404-
pull_candidate_image_name="${base_image_name}"
401+
pull_candidate_image_name="${base_image_name}"
405402
fi
406403
407404
local image_actually_used_or_pulled=""

docker/scripts/docker_base.sh

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ function geo_specific_config() {
3333
info "Setup geolocation specific configurations for ${geo}"
3434
if [[ "${geo}" == "cn" ]]; then
3535
info "GeoLocation settings for Mainland China"
36-
GEO_REGISTRY="registry.baidubce.com"
36+
GEO_REGISTRY="registry.cn-hangzhou.aliyuncs.com"
3737
else
3838
warning "GeoLocation settings for ${geo} is not ready, fallback to default"
3939
fi

modules/common/adapters/BUILD

Lines changed: 18 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,32 @@
1-
load("@rules_cc//cc:defs.bzl", "cc_library")
1+
load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library")
22
load("//tools:cpplint.bzl", "cpplint")
33
load("//tools/install:install.bzl", "install")
44

5+
cc_binary(
6+
name = "libadapter_gflags.so",
7+
srcs = [
8+
"adapter_gflags.cc",
9+
"adapter_gflags.h",
10+
],
11+
linkshared = True,
12+
linkstatic = True,
13+
visibility = ["//visibility:public"],
14+
deps = [
15+
"@com_github_gflags_gflags//:gflags",
16+
],
17+
)
18+
519
cc_library(
620
name = "adapter_gflags",
721
srcs = [
8-
"adapter_gflags.cc",
22+
":libadapter_gflags.so",
923
],
1024
hdrs = ["adapter_gflags.h"],
25+
visibility = ["//visibility:public"],
1126
deps = [
1227
"@com_github_gflags_gflags//:gflags",
1328
],
14-
visibility = ["//visibility:public"],
29+
alwayslink = True,
1530
)
1631

1732
cpplint()

modules/common_msgs/monitor_msgs/monitor_log.proto

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@ message MonitorMessageItem {
2727
DELPHI_ESR = 19;
2828
STORYTELLING = 20;
2929
TASK_MANAGER = 21;
30+
NANO_RADAR = 22;
3031
}
3132

3233
optional MessageSource source = 1 [default = UNKNOWN];

modules/common_msgs/sensor_msgs/BUILD

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -306,3 +306,23 @@ py_proto_library(
306306
name = "radar_py_pb2",
307307
deps = [":radar_proto"],
308308
)
309+
310+
cc_proto_library(
311+
name = "nano_radar_cc_proto",
312+
deps = [
313+
":nano_radar_proto",
314+
],
315+
)
316+
317+
proto_library(
318+
name = "nano_radar_proto",
319+
srcs = ["nano_radar.proto"],
320+
deps = [
321+
"//modules/common_msgs/basic_msgs:header_proto",
322+
],
323+
)
324+
325+
py_proto_library(
326+
name = "nano_radar_py_pb2",
327+
deps = [":nano_radar_proto"],
328+
)
Lines changed: 146 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,146 @@
1+
syntax = "proto2";
2+
3+
package apollo.drivers;
4+
5+
import "modules/common_msgs/basic_msgs/header.proto";
6+
7+
message NanoObjectListStatus_60A {
8+
optional int32 nof_objects = 1 [default = 0];
9+
optional int32 meas_counter = 2 [default = -1];
10+
optional int32 interface_version = 3;
11+
}
12+
13+
14+
15+
message NanoRadarState_201 {
16+
enum OutputType {
17+
OUTPUT_TYPE_NONE = 0;
18+
OUTPUT_TYPE_OBJECTS = 1;
19+
OUTPUT_TYPE_CLUSTERS = 2;
20+
OUTPUT_TYPE_ERROR = 3;
21+
}
22+
23+
enum RcsThreshold {
24+
RCS_THRESHOLD_STANDARD = 0;
25+
RCS_THRESHOLD_HIGH_SENSITIVITY = 1;
26+
RCS_THRESHOLD_ERROR = 2;
27+
}
28+
29+
optional uint32 max_distance = 1;
30+
optional uint32 radar_power = 2;
31+
optional OutputType output_type = 3;
32+
optional RcsThreshold rcs_threshold = 4;
33+
optional bool send_quality = 5;
34+
optional bool send_ext_info = 6;
35+
}
36+
37+
message NanoSoftwareVersion_700 {
38+
optional uint32 soft_major_release = 1;
39+
optional uint32 soft_minor_release = 2;
40+
optional uint32 soft_patch_level = 3;
41+
}
42+
43+
message NanoCollisionDetectionRegionState_402 {
44+
// x axis ^
45+
// | longitude_dist
46+
// P2(Long2,Lat2) |
47+
// ----------------------------------
48+
// | | |
49+
// | | |
50+
// | | |
51+
// ----------------------------------
52+
// | P1(Long1,Lat1)
53+
// |
54+
// | lateral_dist
55+
// --------------------->
56+
// y axis
57+
// ooooooooooooo //radar front surface max:50m x 50m
58+
optional uint32 region_id = 1;
59+
optional uint32 region_max_output_number = 2;
60+
optional double point1_longitude = 3;
61+
optional double point1_lateral = 4;
62+
optional double point2_longitude = 5;
63+
optional double point2_lateral = 6;
64+
optional bool coordinates_valid = 7;
65+
optional bool activation_valid = 8;
66+
}
67+
68+
message NanoRadarObs {
69+
// x axis ^
70+
// | longitude_dist
71+
// |
72+
// |
73+
// |
74+
// | lateral_dist
75+
// | y axis
76+
// ----------------->
77+
// ooooooooooooo //radar front surface 77GHz
78+
79+
optional apollo.common.Header header = 1;
80+
optional bool clusterortrack = 2; // 0 = track, 1 = cluster
81+
optional int32 obstacle_id = 3; // obstacle Id
82+
// longitude distance to the radar; (+) = target far away the radar unit = m
83+
optional double longitude_dist = 4;
84+
// lateral distance to the radar; (+) = right; unit = m
85+
optional double lateral_dist = 5;
86+
// longitude velocity to the radar; (+) = forward; unit = m/s
87+
optional double longitude_vel = 6;
88+
// lateral velocity to the radar; (+) = right; unit = m/s
89+
optional double lateral_vel = 7;
90+
// obstacle Radar Cross-Section; unit = dBsm
91+
optional double rcs = 8;
92+
// 0 = moving, 1 = stationary, 2 = oncoming, 3 = stationary candidate
93+
// 4 = unknown, 5 = crossing stationary, 6 = crossing moving, 7 = stopped
94+
optional int32 dynprop = 9;
95+
// longitude distance standard deviation to the radar; (+) = forward; unit = m
96+
optional double longitude_dist_rms = 10;
97+
// lateral distance standard deviation to the radar; (+) = left; unit = m
98+
optional double lateral_dist_rms = 11;
99+
// longitude velocity standard deviation to the radar; (+) = forward; unit =
100+
// m/s
101+
optional double longitude_vel_rms = 12;
102+
// lateral velocity standard deviation to the radar; (+) = left; unit = m/s
103+
optional double lateral_vel_rms = 13;
104+
// obstacle probability of existence
105+
optional double probexist = 14;
106+
107+
// The following is only valid for the track object message
108+
// 0 = deleted, 1 = new, 2 = measured, 3 = predicted, 4 = deleted for, 5 = new
109+
// from merge
110+
optional int32 meas_state = 15;
111+
// longitude acceleration to the radar; (+) = forward; unit = m/s2
112+
optional double longitude_accel = 16;
113+
// lateral acceleration to the radar; (+) = left; unit = m/s2
114+
optional double lateral_accel = 17;
115+
// orientation angle to the radar; (+) = counterclockwise; unit = degree
116+
optional double oritation_angle = 18;
117+
// longitude acceleration standard deviation to the radar; (+) = forward; unit
118+
// = m/s2
119+
optional double longitude_accel_rms = 19;
120+
// lateral acceleration standard deviation to the radar; (+) = left; unit =
121+
// m/s2
122+
optional double lateral_accel_rms = 20;
123+
// orientation angle standard deviation to the radar; (+) = counterclockwise;
124+
// unit = degree
125+
optional double oritation_angle_rms = 21;
126+
optional double length = 22; // obstacle length; unit = m
127+
optional double width = 23; // obstacle width; unit = m
128+
// 0: point; 1: car; 2: truck; 3: pedestrian; 4: motorcycle; 5: bicycle; 6:
129+
// wide; 7: unknown
130+
optional int32 obstacle_class = 24;
131+
// Object Range
132+
optional double obstacle_range = 25;
133+
// Object Velocity
134+
optional double obstacle_vel = 26;
135+
// Object Angle
136+
optional double obstacle_angle = 27;
137+
}
138+
139+
message NanoRadar {
140+
optional apollo.common.Header header = 1;
141+
repeated NanoRadarObs contiobs = 2; // conti radar obstacle array
142+
optional NanoRadarState_201 radar_state = 3;
143+
optional NanoCollisionDetectionRegionState_402 radar_region_state = 4;
144+
optional NanoObjectListStatus_60A object_list_status = 6;
145+
optional NanoSoftwareVersion_700 software_version = 7;
146+
}

modules/control/controller/lon_speed_controller.cc

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -177,7 +177,12 @@ Status LonSpeedController::ComputeControlCommand(
177177
speed_offset = station_leadlag_controller_.Control(speed_offset, ts);
178178
}
179179

180-
double desired_speed_cmd = debug->preview_speed_reference() + speed_offset;
180+
double desired_speed_cmd = 0.0;
181+
if (FLAGS_enable_speed_station_preview) {
182+
desired_speed_cmd = debug->preview_speed_reference() + speed_offset;
183+
} else {
184+
desired_speed_cmd = debug->speed_reference() + speed_offset;
185+
}
181186

182187
// Check the steer command in reverse trajectory if the current steer target
183188
// is larger than previous target, free the acceleration command, wait for

modules/drivers/gnss/stream/raw_stream.cc

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -492,7 +492,14 @@ void RawStream::RtkSpin() {
492492
return;
493493
}
494494
while (cyber::OK()) {
495-
size_t length = in_rtk_stream_->read(buffer_rtk_, BUFFER_SIZE);
495+
size_t length = 0;
496+
try {
497+
length = in_rtk_stream_->read(buffer_rtk_, BUFFER_SIZE);
498+
} catch (std::runtime_error &e) {
499+
AERROR << "Read RTK stream failed: " << e.what()
500+
<< ". Will retry reading next time. "
501+
<< "Please check if the network connection is stable.";
502+
}
496503
if (length > 0) {
497504
if (rtcm_stream_ != nullptr) {
498505
rtcm_stream_->write(reinterpret_cast<const char *>(buffer_rtk_),
Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library")
2+
load("//tools:cpplint.bzl", "cpplint")
3+
4+
package(default_visibility = ["//visibility:public"])
5+
6+
LIDAR_COMPENSATOR_COPTS = ['-DMODULE_NAME=\\"lidar_compensator\\"']
7+
8+
filegroup(
9+
name = "runtime_data",
10+
srcs = glob([
11+
"conf/*.txt",
12+
"conf/*.conf",
13+
"dag/*.dag",
14+
"launch/*.launch",
15+
]),
16+
)
17+
18+
cc_binary(
19+
name = "liblidar_compensator_component.so",
20+
linkshared = True,
21+
linkstatic = True,
22+
deps = [
23+
":lidar_compensator_component_lib",
24+
],
25+
)
26+
27+
cc_library(
28+
name = "lidar_compensator_component_lib",
29+
srcs = [
30+
"compensator.cc",
31+
"lidar_compensator_component.cc",
32+
],
33+
hdrs = [
34+
"compensator.h",
35+
"lidar_compensator_component.h",
36+
],
37+
copts = LIDAR_COMPENSATOR_COPTS,
38+
deps = [
39+
"//cyber",
40+
"//modules/common/adapters:adapter_gflags",
41+
"//modules/common/latency_recorder",
42+
"//modules/common_msgs/sensor_msgs:pointcloud_cc_proto",
43+
"//modules/drivers/lidar/compensator/proto:lidar_compensator_config_cc_proto",
44+
"//modules/transform:buffer",
45+
"@eigen",
46+
],
47+
alwayslink = True,
48+
)
49+
50+
cpplint()

0 commit comments

Comments
 (0)