Skip to content

Commit

Permalink
fix: aem and lidar driver bugfix
Browse files Browse the repository at this point in the history
- cyber:
	 - 24dc9440e8 fix(aem): fix aem-enter and gtsam,openss install
- docs:
	 - 15727616bc fix(docs): add calibration document supplement
- drivers:
	 - 355937ba82 fix(lidar): fix lslidar driver
	 - 4e675ff980 Commit code for CXZL gnss module (#15558)

Signed-off-by: wangchuang03 <wangchuang03@baidu.com>
Change-Id: Ic922257c66adc045259853ba13c104cca4054f72
  • Loading branch information
wangchuang03 committed Dec 31, 2024
1 parent 2c20d75 commit c48541b
Show file tree
Hide file tree
Showing 9 changed files with 109 additions and 106 deletions.
4 changes: 3 additions & 1 deletion aem/aem-bootstrap
Original file line number Diff line number Diff line change
Expand Up @@ -45,13 +45,15 @@ Options:

start() {
local use_origin_dv=0
local log_subfix=""
if [[ -z "${APOLLO_DISTRIBUTION_VERSION}" ]]; then
warn "APOLLO_DISTRIBUTION_VERSION is not set. fallback to 8.0"
buildtool bootstrap start dreamview-dev
buildtool bootstrap start monitor-dev
else
case "$1" in
--plus)
log_subfix="_plus"
buildtool bootstrap start dreamview_plus
buildtool bootstrap start monitor
;;
Expand All @@ -75,7 +77,7 @@ start() {
if [[ "${http_status}" == 200 ]]; then
info "dreamview is started at ${dv_full_url}"
else
error "failed to start dreamview, please check the logs ( ${APOLLO_ENV_ROOT}/opt/apollo/neo/data/log/dreamview.log or ${APOLLO_ENV_ROOT}/opt/apollo/neo/data/log/monitor.log ) for more details."
error "failed to start dreamview, please check the logs ( data/log/dreamview${log_subfix}.INFO or data/log/monitor.INFO ) for more details."
fi
}

Expand Down
3 changes: 3 additions & 0 deletions aem/aem-enter
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ execute() {

parse_arguments "$@"

# compatible for versions before 10.0
export APOLLO_ENV_CONTAINER_NAME="${APOLLO_ENV_CONTAINER_PREFIX}${APOLLO_ENV_NAME}"

[[ -f "${APOLLO_ENVS_ROOT}/${APOLLO_ENV_NAME}/env.config" ]] && set -a && source "${APOLLO_ENVS_ROOT}/${APOLLO_ENV_NAME}/env.config" && set +a

apollo_enter_env
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ PATCHES=(
)

src_prepare_pre() {
# apt_get_update_and_install libboost-all-dev
apt_get_update_and_install libboost-all-dev
apt_get_update_and_install apollo-neo-3rd-boost
# TODO: pack to 3rd-boost release tarball
boost_cmake_files_url='https://apollo-system.cdn.bcebos.com/archive/10.0/3rd-boost_1.74.0_cmake_files.tar.gz'
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,10 @@ src_configure() {
popd
}

pkg_install() {
:
}

pkg_install_post() {
if [[ -d "${INSTALL_PREFIX}/lib64" ]] && [[ ! -e "${INSTALL_PREFIX}/lib" ]]; then
ln -snf lib64 "${INSTALL_PREFIX}/lib"
Expand Down
2 changes: 1 addition & 1 deletion aem/env.sh
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ else
export AEM_HOME=${AEM_HOME:-$(dirname $(realpath $0))}
fi
export AEM_SYS_SHARE=${AEM_SYS_SHARE:-${AEM_HOME}/share/aem}
export AEM_VERSION='10.0.0-rc1-r3'
export AEM_VERSION='10.0.0-rc1-r4'

export APOLLO_ENVS_ROOT=${APOLLO_ENVS_ROOT:-${HOME}/.aem/envs}
export APOLLO_ENV_NAME="${USER}"
Expand Down
6 changes: 4 additions & 2 deletions docs/工具使用/标定工具/动力学标定.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,10 @@

## 模块启动依赖

标定工具依赖定位 Localization、GPS 以及 Caubus 模块,标定前请您确保相关模块启动正常。

标定工具依赖定位 Localization、GPS 以及 Caubus 模块,标定前请您确保相关模块启动正常。因为动力学标定依赖tensorflow,请执行以下命令安装tensorflow环境。
```bash
pip3 show tensorflow >/dev/null || pip3 install tensorflow==2.11.0 -i https://pypi.tuna.tsinghua.edu.cn/simple
```
## 操作步骤

### 步骤一:参数确认
Expand Down
2 changes: 2 additions & 0 deletions docs/工具使用/标定工具/环境配置.md
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ camera_calib { # camera标定配置
lidar_rotation: 0 # lidar点云旋转角度,默认是0度,逆时针为正
intrinsics_filename: "/apollo/modules/perception/data/params/camera_front_12mm_intrinsics.yaml" # 内参文件路径
output_filename: "/apollo/modules/perception/data/params/camera_front_12mm_extrinsics.yaml" # 标定结果文件路径(文件要存在并有写入权限)
lidar_to_imu_extrinsic_file_path: "/apollo/modules/perception/data/params/lidar16_back_imu_extrinsics.yaml" #lidar-imu外参路径
},
{
name: "camera_front_6mm" # camera名字,前端展示用
Expand All @@ -87,6 +88,7 @@ camera_calib { # camera标定配置
lidar_rotation: 0 # lidar点云旋转角度,默认是0度,逆时针为正
intrinsics_filename: "/apollo/modules/perception/data/params/camera_front_6mm_intrinsics.yaml" # 内参文件路径
output_filename: "/apollo/modules/perception/data/params/camera_front_6mm_extrinsics.yaml" # 标定结果文件路径(文件要存在并有写入权限)
lidar_to_imu_extrinsic_file_path: "/apollo/modules/perception/data/params/lidar16_back_imu_extrinsics.yaml" #lidar-imu外参路径
}
]
}
Expand Down
80 changes: 34 additions & 46 deletions modules/drivers/lidar/common/sync_queue.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,58 +65,46 @@ namespace drivers {
template <typename T>
class SyncQueue {
public:
inline size_t push(const T& value) {
bool empty = false;
size_t size = 0;

{
std::lock_guard<std::mutex> lg(mtx_);
empty = queue_.empty();
queue_.push(value);
size = queue_.size();
}

if (empty)
cv_.notify_one();
return size;
inline size_t push(const T& value) {
std::lock_guard<std::mutex> lg(mtx_);
queue_.push(value);
return queue_.size();
}

inline T pop() {
T value;

std::lock_guard<std::mutex> lg(mtx_);
if (!queue_.empty()) {
value = queue_.front();
queue_.pop();
}

inline T pop() {
T value;

std::lock_guard<std::mutex> lg(mtx_);
if (!queue_.empty()) {
value = queue_.front();
queue_.pop();
}

return value;
return value;
}

inline bool popWait(T& ret_ele, unsigned int usec = 1000000) {
{
std::lock_guard<std::mutex> lg(mtx_);
if (!queue_.empty()) {
ret_ele = queue_.front();
queue_.pop();
return true;
}
}
std::this_thread::sleep_for(std::chrono::microseconds(usec));
return false;
}

inline bool popWait(T& ret_ele, unsigned int usec = 1000000) {
{
std::lock_guard<std::mutex> lg(mtx_);
if (!queue_.empty()) {
ret_ele = queue_.front();
queue_.pop();
return true;
}
}

std::this_thread::sleep_for(std::chrono::microseconds(1000));
return false;
}

inline void clear() {
std::queue<T> empty;
std::lock_guard<std::mutex> lg(mtx_);
swap(empty, queue_);
}
inline void clear() {
std::queue<T> empty;
std::lock_guard<std::mutex> lg(mtx_);
swap(empty, queue_);
}

private:
std::queue<T> queue_;
std::mutex mtx_;
std::condition_variable cv_;
std::queue<T> queue_;
std::mutex mtx_;
};

} // namespace drivers
Expand Down
112 changes: 57 additions & 55 deletions modules/drivers/lidar/lslidar/component/lslidar_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,84 +21,86 @@ namespace drivers {
namespace lslidar {

LslidarComponent::~LslidarComponent() {
if (device_thread_->joinable()) {
device_thread_->join();
}
if (pointcloud_convert_thread_->joinable()) {
pointcloud_convert_thread_->join();
}
if (device_thread_->joinable()) {
device_thread_->join();
}
if (pointcloud_convert_thread_->joinable()) {
pointcloud_convert_thread_->join();
}
}

bool LslidarComponent::Init() {
if (!GetProtoConfig(&conf_)) {
AERROR << "load config error, file:" << config_file_path_;
return false;
}
if (!GetProtoConfig(&conf_)) {
AERROR << "load config error, file:" << config_file_path_;
return false;
}

this->InitBase(conf_.config_base());
this->InitBase(conf_.config_base());

driver::LslidarDriver *driver
= driver::LslidarDriverFactory::CreateDriver(conf_);
if (!driver) {
return false;
}
dvr_.reset(driver);
dvr_->Init();
// spawn device poll thread
// runing_ = true;
device_thread_ = std::shared_ptr<std::thread>(new std::thread(
std::bind(&LslidarComponent::DevicePollProcess, this)));
pointcloud_convert_thread_ = std::make_shared<std::thread>(
&LslidarComponent::ScanQueuePollProcess, this);
driver::LslidarDriver *driver =
driver::LslidarDriverFactory::CreateDriver(conf_);
if (!driver) {
return false;
}
dvr_.reset(driver);
dvr_->Init();
// spawn device poll thread
// runing_ = true;
device_thread_ = std::shared_ptr<std::thread>(
new std::thread(std::bind(&LslidarComponent::DevicePollProcess, this)));
pointcloud_convert_thread_ = std::make_shared<std::thread>(
&LslidarComponent::ScanQueuePollProcess, this);

converter_ = std::make_shared<parser::Convert>();
converter_->init(conf_);
converter_ = std::make_shared<parser::Convert>();
converter_->init(conf_);

return true;
return true;
}

void LslidarComponent::ReadScanCallback(
const std::shared_ptr<LslidarScan> &scan_message) {
HandleScanFrame(scan_message);
const std::shared_ptr<LslidarScan> &scan_message) {
HandleScanFrame(scan_message);
}

void LslidarComponent::DevicePollProcess() {
while (!apollo::cyber::IsShutdown()) {
// poll device until end of file
std::shared_ptr<LslidarScan> scan
= std::make_shared<apollo::drivers::lslidar::LslidarScan>();
while (!apollo::cyber::IsShutdown()) {
// poll device until end of file
std::shared_ptr<LslidarScan> scan =
std::make_shared<apollo::drivers::lslidar::LslidarScan>();

bool ret = dvr_->Poll(scan);
if (ret) {
common::util::FillHeader("lslidar", scan.get());
AINFO << "publish scan!";
double time1 = apollo::cyber::Time().Now().ToSecond();
this->WriteScan(scan);
double time2 = apollo::cyber::Time().Now().ToSecond();
AINFO << "apollo::cyber::Time((time2 - time1)"
<< apollo::cyber::Time((time2 - time1) / 2.0).ToNanosecond();
scan_queue_.push(scan);
} else {
AWARN << "device poll failed";
}
bool ret = dvr_->Poll(scan);
if (ret) {
common::util::FillHeader("lslidar", scan.get());
AINFO << "publish scan!";
double time1 = apollo::cyber::Time().Now().ToSecond();
this->WriteScan(scan);
double time2 = apollo::cyber::Time().Now().ToSecond();
AINFO << "apollo::cyber::Time((time2 - time1)"
<< apollo::cyber::Time((time2 - time1) / 2.0).ToNanosecond();
scan_queue_.push(scan);
} else {
AWARN << "device poll failed";
}
}

AERROR << "CompLslidarDriver thread exit";
AERROR << "CompLslidarDriver thread exit";
}

void LslidarComponent::ScanQueuePollProcess() {
std::shared_ptr<LslidarScan> scan_frame;
while (!apollo::cyber::IsShutdown() && scan_queue_.popWait(scan_frame)) {
HandleScanFrame(scan_frame);
std::shared_ptr<LslidarScan> scan_frame;
while (!apollo::cyber::IsShutdown()) {
if (scan_queue_.popWait(scan_frame)) {
HandleScanFrame(scan_frame);
}
}
}

void LslidarComponent::HandleScanFrame(
const std::shared_ptr<LslidarScan> &scan_frame) {
std::shared_ptr<apollo::drivers::PointCloud> point_cloud_out
= this->AllocatePointCloud();
converter_->ConvertPacketsToPointcloud(scan_frame, point_cloud_out);
this->WritePointCloud(point_cloud_out);
const std::shared_ptr<LslidarScan> &scan_frame) {
std::shared_ptr<apollo::drivers::PointCloud> point_cloud_out =
this->AllocatePointCloud();
converter_->ConvertPacketsToPointcloud(scan_frame, point_cloud_out);
this->WritePointCloud(point_cloud_out);
}

} // namespace lslidar
Expand Down

0 comments on commit c48541b

Please sign in to comment.