未验证 提交 11104c3d 编写于 作者: L liuxu 提交者: GitHub

Refactor Lidar drivers (#13245)

* drivers: lidar refactor lidar/dirver to add factory pattern

* Lidar Driver: fix deconstruc bug

* Lidar Driver: fix some format

* Lidar Driver: fix some format

Lidar Driver: remove explict

Lidar Drivers: buildifer BUILD

* Lidar Driver: init node_

* Lidar Driver: modify lidar conf
Co-authored-by: Nliuxu <liuxu20@baidu.com>
上级 20e5ac08
load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
name = "lidar_driver_component_lib",
srcs = ["lidar_driver_component.cc"],
hdrs = ["lidar_driver_component.h"],
deps = [
"//cyber",
"//modules/drivers/lidar/common/driver_factory:lidar_driver_factory",
"//modules/drivers/lidar/proto:config",
],
)
cc_binary(
name = "liblidar_driver_component.so",
linkshared = True,
linkstatic = False,
deps = [":lidar_driver_component_lib"],
)
cpplint()
load("@rules_cc//cc:defs.bzl", "cc_library")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
name = "lidar_driver_factory",
srcs = ["lidar_driver_factory.cc"],
hdrs = ["lidar_driver_factory.h"],
deps = [
":driver_base",
"//cyber",
"//modules/common/util:factory",
"//modules/drivers/lidar/hesai/driver",
"//modules/drivers/lidar/proto:config",
"//modules/drivers/lidar/proto:lidar_parameter",
"//modules/drivers/lidar/robosense/driver",
"//modules/drivers/lidar/velodyne/driver",
],
)
cc_library(
name = "driver_base",
hdrs = ["driver_base.h"],
deps = [
"//modules/common/util",
"//modules/common/util:factory",
],
)
cpplint()
/******************************************************************************
* Copyright 2020 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
/**
* @file
* @brief Defines the CanFrame struct and CanClient interface.
*/
#pragma once
#include <cstdint>
#include <cstring>
#include <memory>
#include <sstream>
#include <string>
#include <vector>
#include "cyber/common/log.h"
#include "cyber/cyber.h"
/**
* @namespace apollo::drivers::lidar
* @brief apollo::drivers::lidar
*/
namespace apollo {
namespace drivers {
namespace lidar {
/**
* @class LidarDriver
* @brief The class which defines the lidar driver .
*/
class LidarDriver {
public:
/**
* @brief Constructor
*/
LidarDriver() {}
explicit LidarDriver(const std::shared_ptr<::apollo::cyber::Node>& node)
: node_(node) {}
/**
* @brief Destructor
*/
virtual ~LidarDriver() = default;
/**
* @brief Initialize the lidar driver.
* @return If the initialization is successful.
*/
virtual bool Init() = 0;
protected:
std::shared_ptr<cyber::Node> node_;
};
} // namespace lidar
} // namespace drivers
} // namespace apollo
/******************************************************************************
* Copyright 2020 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/drivers/lidar/common/driver_factory/lidar_driver_factory.h"
#include "modules/drivers/lidar/hesai/driver/driver.h"
#include "modules/drivers/lidar/robosense/driver/driver.h"
#include "modules/drivers/lidar/velodyne/driver/driver.h"
namespace apollo {
namespace drivers {
namespace lidar {
LidarDriverFactory::LidarDriverFactory() {}
LidarDriverFactory::LidarDriverFactory(
const apollo::drivers::lidar::config& config) {}
void LidarDriverFactory::RegisterLidarClients() {
Register(LidarParameter::HESAI,
[](const std::shared_ptr<::apollo::cyber::Node>& node,
const apollo::drivers::lidar::config& config) -> LidarDriver* {
return new hesai::HesaiDriver(node, config);
});
Register(LidarParameter::ROBOSENSE,
[](const std::shared_ptr<::apollo::cyber::Node>& node,
const apollo::drivers::lidar::config& config) -> LidarDriver* {
return new robosense::RobosenseDriver(node, config);
});
Register(LidarParameter::VELODYNE,
[](const std::shared_ptr<::apollo::cyber::Node>& node,
const apollo::drivers::lidar::config& config) -> LidarDriver* {
return velodyne::VelodyneDriverFactory::CreateDriver(
node, config.velodyne());
});
}
std::unique_ptr<LidarDriver> LidarDriverFactory::CreateLidarDriver(
const std::shared_ptr<::apollo::cyber::Node>& node,
const apollo::drivers::lidar::config& parameter) {
auto factory = CreateObject(parameter.brand(), node, parameter);
if (!factory) {
AERROR << "Failed to create lidar with parameter: "
<< parameter.DebugString();
}
return factory;
}
} // namespace lidar
} // namespace drivers
} // namespace apollo
/******************************************************************************
* Copyright 2020 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
/**
* @file
* @brief Defines the LidarFactory class.
*/
#pragma once
#include <memory>
#include <unordered_map>
#include "modules/drivers/lidar/proto/config.pb.h"
#include "modules/drivers/lidar/proto/lidar_parameter.pb.h"
#include "cyber/common/macros.h"
#include "cyber/cyber.h"
#include "modules/common/util/factory.h"
#include "modules/drivers/lidar/common/driver_factory/driver_base.h"
#include "modules/drivers/lidar/hesai/parser/parser.h"
/**
* @namespace apollo::drivers::lidar
*
*/
namespace apollo {
namespace drivers {
namespace lidar {
class LidarDriverFactory
: public apollo::common::util::Factory<
LidarParameter::LidarBrand, LidarDriver,
LidarDriver* (*)(const std::shared_ptr<::apollo::cyber::Node>& node,
const apollo::drivers::lidar::config& config)> {
public:
LidarDriverFactory(const apollo::drivers::lidar::config& config);
/**
* @brief Register the lidar driver of all brands. This function call the
* Function apollo::common::util::Factory::Register() for all of the
* lidar.
*/
void RegisterLidarClients();
/**
* @brief Create a pointer to a specified brand of lidar. The brand is
* set in the parameter.
* @param parameter The parameter to create the CAN client.
* @return A pointer to the created CAN client.
*/
std::unique_ptr<LidarDriver> CreateLidarDriver(
const std::shared_ptr<::apollo::cyber::Node>& node,
const apollo::drivers::lidar::config& parameter);
protected:
private:
DECLARE_SINGLETON(LidarDriverFactory)
};
} // namespace lidar
} // namespace drivers
} // namespace apollo
world_frame_id: "world"
transform_query_timeout: 0.02
output_channel: "/apollo/sensor/lidar16/compensator/PointCloud2"
frame_id: "velodyne128"
scan_channel: "/apollo/sensor/lidar16/Scan"
rpm: 600.0
model: VLP16
mode: STRONGEST
prefix_angle: 18000
firing_data_port: 2369
positioning_data_port: 8309
use_sensor_sync: false
max_range: 100.0
min_range: 0.9
use_gps_time: true
calibration_online: false
calibration_file: "/apollo/modules/drivers/lidar/velodyne/params/VLP16_calibration.yaml"
organized: false
convert_channel_name: "/apollo/sensor/lidar16/PointCloud2"
use_poll_sync: true
is_main_frame: true
brand: ROBOSENSE
velodyne {
frame_id: "velodyne128"
scan_channel: "/apollo/sensor/lidar16/Scan"
rpm: 600
model: VLP16
prefix_angle: 18000
firing_data_port: 2369
positioning_data_port: 8309
use_sensor_sync: false
max_range: 100
min_range: 0.9
calibration_online: false
calibration_file: "/apollo/modules/drivers/lidar/velodyne/params/VLP16_calibration.yaml"
organized: false
convert_channel_name: "/apollo/sensor/lidar16/PointCloud2"
mode: STRONGEST
use_gps_time: true
use_poll_sync: true
is_main_frame: true
}
hesai {
model: HESAI64
ip: "192.168.20.13"
lidar_recv_port: 2368
gps_recv_port: 10110
start_angle: 0
pointcloud_channel: "/apollo/sensor/hesai64/PointCloud2"
time_zone: 8
frame_id: "hesai64"
scan_channel: "/apollo/sensor/hesai64/Scan"
}
robosense {
model: "RS32"
frame_id: "rslidar_32"
ip: "192.168.1.200"
msop_port: 6699
difop_port: 7788
echo_mode: 1
start_angle: 0
end_angle: 360
min_distance: 0
max_distance: 200
cut_angle: 0
pointcloud_channel: "/apollo/sensor/rs32/PointCloud2"
scan_channel: "/apollo/sensor/rs32/Scan"
use_lidar_clock: false
}
world_frame_id: "world"
transform_query_timeout: 0.02
output_channel: "/apollo/sensor/lidar16/compensator/PointCloud2"
# Define all coms in DAG streaming.
module_config {
module_library : "/apollo/bazel-bin/modules/drivers/lidar/liblidar_driver_component.so"
components {
class_name : "LidarDriverComponent"
config {
name : "lidar_driver"
config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_config.pb.txt"
readers {channel: "/apollo/sensor/lidar/driver"}
}
}
}
module_config {
module_library : "/apollo/bazel-bin/modules/drivers/lidar/velodyne/compensator/libvelodyne_compensator_component.so"
components {
class_name : "CompensatorComponent"
config {
name : "RS16_Compensator"
config_file_path : "/apollo/modules/drivers/lidar/robosense/conf/rs16_compensator.pb.txt"
readers {channel: "/apollo/sensor/rs16/PointCloud2"}
}
}
}
# Define all coms in DAG streaming.
module_config {
module_library : "/apollo/bazel-bin/modules/drivers/lidar/velodyne/driver/libvelodyne_driver_component.so"
components {
class_name : "VelodyneDriverComponent"
config {
name : "velodyne_driver"
config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_conf.pb.txt"
}
module_config {
module_library : "/apollo/bazel-bin/modules/drivers/lidar/liblidar_driver_component.so"
components {
class_name : "LidarDriverComponent"
config {
name : "lidar_driver"
config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_config.pb.txt"
readers {channel: "/apollo/sensor/lidar/driver"}
}
}
}
module_config {
......@@ -18,7 +18,7 @@ module_config {
class_name : "VelodyneConvertComponent"
config {
name : "velodyne_convert"
config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_conf.pb.txt"
config_file_path : "/apollo/modules/drivers/lidar/velodyne/conf/velodyne16_front_center_conf.pb.txt"
readers {channel: "/apollo/sensor/lidar16/Scan"}
}
}
......@@ -31,10 +31,8 @@ module_config {
class_name : "CompensatorComponent"
config {
name : "velodyne_compensator"
config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_fusion_compensator.pb.txt"
config_file_path : "/apollo/modules/drivers/lidar/velodyne/conf/velodyne16_fusion_compensator.pb.txt"
readers {channel: "/apollo/sensor/lidar16/PointCloud2"}
}
}
}
......@@ -10,8 +10,8 @@ cc_binary(
linkshared = True,
linkstatic = False,
deps = [
":hesai_component",
":hesai_convert_component",
"//modules/drivers/lidar/hesai/driver:hesai_component",
],
)
......@@ -21,36 +21,10 @@ cc_library(
hdrs = ["parser/hesai_convert_component.h"],
copts = HESAI_COPTS,
deps = [
":driver",
":parser_factory",
"//cyber",
"//modules/drivers/lidar/hesai/proto:config_cc_proto",
],
)
cc_library(
name = "hesai_component",
srcs = ["driver/hesai_component.cc"],
hdrs = ["driver/hesai_component.h"],
copts = HESAI_COPTS,
deps = [
":driver",
":parser_factory",
"//cyber",
"//modules/drivers/lidar/hesai/proto:config_cc_proto",
],
)
cc_library(
name = "driver",
srcs = ["driver/driver.cc"],
hdrs = ["driver/driver.h"],
copts = HESAI_COPTS,
deps = [
":parser",
":type_defs",
":udp_input",
"//cyber",
"//modules/drivers/lidar/hesai/driver",
"//modules/drivers/lidar/proto:hesai_config_cc_proto",
],
)
......@@ -98,8 +72,8 @@ cc_library(
":tcp_cmd_client",
":type_defs",
"//cyber",
"//modules/drivers/lidar/hesai/proto:config_cc_proto",
"//modules/drivers/lidar/hesai/proto:hesai_cc_proto",
"//modules/drivers/lidar/proto:hesai_cc_proto",
"//modules/drivers/lidar/proto:hesai_config_cc_proto",
"//modules/drivers/proto:pointcloud_cc_proto",
],
)
......
load("@rules_cc//cc:defs.bzl", "cc_library")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
HESAI_COPTS = ['-DMODULE_NAME=\\"hesai\\"']
cc_library(
name = "hesai_component",
srcs = ["hesai_component.cc"],
hdrs = ["hesai_component.h"],
copts = HESAI_COPTS,
deps = [
":driver",
"//cyber",
"//modules/drivers/lidar/hesai:parser_factory",
"//modules/drivers/lidar/proto:hesai_config_cc_proto",
],
)
cc_library(
name = "driver",
srcs = ["driver.cc"],
hdrs = ["driver.h"],
copts = HESAI_COPTS,
deps = [
"//cyber",
"//modules/drivers/lidar/common/driver_factory:driver_base",
"//modules/drivers/lidar/hesai:parser",
"//modules/drivers/lidar/hesai:parser_factory",
"//modules/drivers/lidar/hesai:type_defs",
"//modules/drivers/lidar/hesai:udp_input",
"//modules/drivers/lidar/proto:config_proto",
],
)
cpplint()
......@@ -25,6 +25,11 @@ bool HesaiDriver::Init() {
AERROR << "node is nullptr";
return false;
}
Parser* hesai_parser = ParserFactory::CreateParser(node_, conf_);
if (hesai_parser == nullptr) {
AERROR << "create parser error";
}
parser_.reset(hesai_parser);
scan_writer_ = node_->CreateWriter<HesaiScan>(conf_.scan_channel());
if (scan_writer_ == nullptr) {
AERROR << "writer:" << conf_.scan_channel()
......
......@@ -28,21 +28,28 @@
#include <thread>
#include <vector>
#include "modules/drivers/lidar/proto/config.pb.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/hesai/parser/parser.h"
#include "modules/drivers/lidar/common/driver_factory/driver_base.h"
#include "modules/drivers/lidar/hesai/input/udp_input.h"
#include "modules/drivers/lidar/hesai/parser/parser.h"
#include "modules/drivers/lidar/hesai/parser/parser_factory.h"
namespace apollo {
namespace drivers {
namespace hesai {
class HesaiDriver {
class HesaiDriver : public apollo::drivers::lidar::LidarDriver {
public:
HesaiDriver(const std::shared_ptr<::apollo::cyber::Node>& node,
const Config& conf, const std::shared_ptr<Parser>& parser)
: node_(node), conf_(conf), parser_(parser) {}
const ::apollo::drivers::lidar::config& conf)
: node_(node), conf_(conf.hesai()) {}
HesaiDriver(const std::shared_ptr<::apollo::cyber::Node>& node,
const ::apollo::drivers::hesai::Config& conf)
: node_(node), conf_(conf) {}
~HesaiDriver() { Stop(); }
bool Init();
bool Init() override;
private:
std::shared_ptr<::apollo::cyber::Node> node_ = nullptr;
......
......@@ -20,19 +20,14 @@ namespace drivers {
namespace hesai {
bool HesaiComponent::Init() {
if (!GetProtoConfig(&conf_)) {
if (!GetProtoConfig(&hesai_conf_)) {
AERROR << "load config error, file:" << config_file_path_;
return false;
}
AINFO << "conf:" << conf_.DebugString();
Parser* parser = ParserFactory::CreateParser(node_, conf_);
if (parser == nullptr) {
AERROR << "create parser error";
return false;
}
parser_.reset(parser);
driver_.reset(new HesaiDriver(node_, conf_, parser_));
AINFO << "conf:" << hesai_conf_.DebugString();
driver_.reset(new HesaiDriver(node_, hesai_conf_));
if (!driver_->Init()) {
AERROR << "driver init error";
......
......@@ -19,7 +19,8 @@
#include <memory>
#include <string>
#include "modules/drivers/lidar/hesai/proto/config.pb.h"
#include "modules/drivers/lidar/proto/config.pb.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/hesai/driver/driver.h"
#include "modules/drivers/lidar/hesai/parser/parser_factory.h"
......@@ -35,8 +36,7 @@ class HesaiComponent : public ::apollo::cyber::Component<> {
private:
std::shared_ptr<HesaiDriver> driver_;
std::shared_ptr<Parser> parser_;
Config conf_;
Config hesai_conf_;
};
CYBER_REGISTER_COMPONENT(HesaiComponent)
......
......@@ -19,8 +19,9 @@
#include <memory>
#include <string>
#include "modules/drivers/lidar/hesai/proto/config.pb.h"
#include "modules/drivers/lidar/hesai/proto/hesai.pb.h"
#include "modules/drivers/lidar/proto/hesai.pb.h"
#include "modules/drivers/lidar/proto/hesai_config.pb.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/hesai/parser/parser_factory.h"
......
......@@ -23,8 +23,8 @@
#include <thread>
#include <vector>
#include "modules/drivers/lidar/hesai/proto/config.pb.h"
#include "modules/drivers/lidar/hesai/proto/hesai.pb.h"
#include "modules/drivers/lidar/proto/hesai_config.pb.h"
#include "modules/drivers/lidar/proto/hesai.pb.h"
#include "modules/drivers/proto/pointcloud.pb.h"
#include "cyber/cyber.h"
......
## Auto generated by `proto_build_generator.py`
load("@rules_proto//proto:defs.bzl", "proto_library")
load("@rules_cc//cc:defs.bzl", "cc_proto_library")
load("//tools:python_rules.bzl", "py_proto_library")
package(default_visibility = ["//visibility:public"])
cc_proto_library(
name = "config_cc_proto",
deps = [
":config_proto",
],
)
proto_library(
name = "config_proto",
srcs = ["config.proto"],
deps = [
":hesai_proto",
],
)
py_proto_library(
name = "config_py_pb2",
deps = [
":config_proto",
":hesai_py_pb2",
],
)
cc_proto_library(
name = "hesai_cc_proto",
deps = [
":hesai_proto",
],
)
proto_library(
name = "hesai_proto",
srcs = ["hesai.proto"],
deps = [
"//modules/common/proto:header_proto",
],
)
py_proto_library(
name = "hesai_py_pb2",
deps = [
":hesai_proto",
"//modules/common/proto:header_py_pb2",
],
)
<cyber>
<module>
<name>lidar_driver</name>
<dag_conf>/apollo/modules/drivers/lidar/dag/velodyne_lidar.dag</dag_conf>
<process_name>lidar_driver</process_name>
</module>
</cyber>
/******************************************************************************
* Copyright 2020 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/drivers/lidar/lidar_driver_component.h"
#include "modules/drivers/lidar/proto/lidar_parameter.pb.h"
namespace apollo {
namespace drivers {
namespace lidar {
LidarDriverComponent::LidarDriverComponent() {}
bool LidarDriverComponent::Init() {
if (!GetProtoConfig(&conf_)) {
AERROR << "load config error, file:" << config_file_path_;
return false;
}
node_ = apollo::cyber::CreateNode("drivers_lidar");
AINFO << "conf:" << conf_.DebugString();
LidarDriverFactory::Instance()->RegisterLidarClients();
driver_ = LidarDriverFactory::Instance()->CreateLidarDriver(node_, conf_);
if (!driver_->Init()) {
AERROR << "driver init error";
return false;
}
return true;
}
} // namespace lidar
} // namespace drivers
} // namespace apollo
/******************************************************************************
* Copyright 2020 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include <memory>
#include "modules/drivers/lidar/proto/config.pb.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/common/driver_factory/lidar_driver_factory.h"
namespace apollo {
namespace drivers {
namespace lidar {
class LidarDriverComponent : public ::apollo::cyber::Component<> {
public:
LidarDriverComponent();
~LidarDriverComponent() {}
bool Init() override;
private:
std::shared_ptr<LidarDriverFactory> lidar_factory_;
apollo::drivers::lidar::config conf_;
std::shared_ptr<::apollo::cyber::Node> node_;
std::unique_ptr<LidarDriver> driver_;
};
CYBER_REGISTER_COMPONENT(LidarDriverComponent)
} // namespace lidar
} // namespace drivers
} // namespace apollo
load("@rules_proto//proto:defs.bzl", "proto_library")
load("@rules_cc//cc:defs.bzl", "cc_library", "cc_proto_library")
load("//tools:python_rules.bzl", "py_proto_library")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_proto_library(
name = "velodyne_cc_proto",
deps = [
":velodyne_proto",
],
)
proto_library(
name = "velodyne_proto",
srcs = ["velodyne.proto"],
deps = [
"//modules/common/proto:header_proto",
],
)
py_proto_library(
name = "velodyne_py_pb2",
deps = [
":velodyne_proto",
"//modules/common/proto:header_py_pb2",
],
)
cc_proto_library(
name = "velodyne_config_cc_proto",
deps = [
":velodyne_config_proto",
],
)
proto_library(
name = "velodyne_config_proto",
srcs = ["velodyne_config.proto"],
deps = [
":velodyne_proto",
],
)
##hesai
py_proto_library(
name = "hesai_py_pb2",
deps = [
":hesai_proto",
"//modules/common/proto:header_py_pb2",
],
)
proto_library(
name = "hesai_proto",
srcs = ["hesai.proto"],
deps = [
"//modules/common/proto:header_proto",
],
)
cc_proto_library(
name = "hesai_cc_proto",
deps = [
":hesai_proto",
],
)
proto_library(
name = "hesai_config_proto",
srcs = ["hesai_config.proto"],
deps = [
":hesai_proto",
],
)
cc_proto_library(
name = "hesai_config_cc_proto",
deps = [
":hesai_config_proto",
],
)
##robosense
cc_library(
name = "robosense_proto",
deps = [
":sensor_robosense_proto",
],
)
cc_proto_library(
name = "sensor_robosense_proto",
deps = [
":robosense_proto_lib",
],
)
proto_library(
name = "robosense_proto_lib",
srcs = [
"robosense.proto",
"robosense_config.proto",
],
deps = [
"//modules/common/proto:header_proto",
],
)
proto_library(
name = "lidar_parameter_proto_lib",
srcs = [
"lidar_parameter.proto",
],
)
cc_proto_library(
name = "lidar_parameter_proto",
deps = [
":lidar_parameter_proto_lib",
],
)
cc_library(
name = "lidar_parameter",
deps = [
":lidar_parameter_proto",
],
)
proto_library(
name = "config_proto_lib",
srcs = [
"config.proto",
],
deps = [
":hesai_config_proto",
":lidar_parameter_proto_lib",
":robosense_proto_lib",
":velodyne_config_proto",
"//modules/common/proto:header_proto",
],
)
cc_proto_library(
name = "config_proto",
deps = [
":config_proto_lib",
],
)
cc_library(
name = "config",
deps = [
":config_proto",
],
)
cpplint()
syntax = "proto2";
package apollo.drivers.lidar;
import "modules/drivers/lidar/proto/hesai_config.proto";
import "modules/drivers/lidar/proto/velodyne_config.proto";
import "modules/drivers/lidar/proto/lidar_parameter.proto";
import "modules/drivers/lidar/proto/robosense_config.proto";
message config {
optional LidarParameter.LidarBrand brand = 1;
optional apollo.drivers.hesai.Config hesai = 2;
optional apollo.drivers.robosense.Config robosense = 3;
optional apollo.drivers.velodyne.Config velodyne = 4;
}
......@@ -2,7 +2,7 @@ syntax = "proto2";
package apollo.drivers.hesai;
import "modules/drivers/lidar/hesai/proto/hesai.proto";
import "modules/drivers/lidar/proto/hesai.proto";
message Config {
optional Model model = 1;
......
syntax = "proto2";
package apollo.drivers.lidar;
message LidarParameter {
enum LidarBrand {
VELODYNE = 0;
HESAI = 1;
ROBOSENSE = 2;
}
enum LidarChannelId {
CHANNEL_ID_ZERO = 0;
CHANNEL_ID_ONE = 1;
CHANNEL_ID_TWO = 2;
CHANNEL_ID_THREE = 3;
}
required LidarBrand brand = 1;
}
......@@ -19,4 +19,3 @@ message Config {
optional string calibration_file=15;
optional bool use_lidar_clock = 16;
}
......@@ -2,7 +2,7 @@ syntax = "proto2";
package apollo.drivers.velodyne;
import "modules/drivers/lidar/velodyne/proto/velodyne.proto";
import "modules/drivers/lidar/proto/velodyne.proto";
message Config {
optional string frame_id = 1;
......
......@@ -9,41 +9,7 @@ cc_binary(
name = "librobosense_driver_component.so",
linkshared = True,
linkstatic = False,
deps = [":robosense_driver_component_lib"],
)
cc_library(
name = "robosense_driver_component_lib",
srcs = [
"driver/robosense_driver_component.cc",
],
hdrs = [
"driver/robosense_driver_component.h",
],
copts = ROBOSENSE_COPTS,
deps = [":driver"],
)
cc_library(
name = "driver",
srcs = [
"driver/driver.cpp",
"driver/utility.cpp",
"input/input.cpp",
],
hdrs = [
"driver/driver.h",
"driver/utility.h",
"input/input.h",
],
copts = ROBOSENSE_COPTS,
deps = [
":decoder_factory",
"//cyber",
"//modules/common/util",
"//modules/drivers/proto:pointcloud_cc_proto",
"//modules/drivers/lidar/robosense/proto:robosense_proto",
],
deps = ["//modules/drivers/lidar/robosense/driver:robosense_driver_component_lib"],
)
cc_library(
......
load("//tools:cpplint.bzl", "cpplint")
load("@rules_cc//cc:defs.bzl", "cc_library")
package(default_visibility = ["//visibility:public"])
ROBOSENSE_COPTS = ['-DMODULE_NAME=\\"robosense\\"']
cc_library(
name = "robosense_driver_component_lib",
srcs = [
"robosense_driver_component.cc",
],
hdrs = [
"robosense_driver_component.h",
],
copts = ROBOSENSE_COPTS,
deps = [
":driver",
"//cyber",
],
)
cc_library(
name = "driver",
srcs = [
"driver.cpp",
"utility.cpp",
],
hdrs = [
"driver.h",
"utility.h",
],
copts = ROBOSENSE_COPTS,
deps = [
"//cyber",
"//modules/common/util",
"//modules/drivers/lidar/common/driver_factory:driver_base",
"//modules/drivers/lidar/proto:config_proto",
"//modules/drivers/lidar/proto:robosense_proto",
"//modules/drivers/lidar/robosense:decoder_factory",
"//modules/drivers/lidar/robosense/input",
"//modules/drivers/proto:pointcloud_cc_proto",
],
)
cpplint()
......@@ -23,7 +23,7 @@ using apollo::cyber::Writer;
using apollo::drivers::PointCloud;
using apollo::drivers::PointXYZIT;
using apollo::drivers::robosense::RobosenseScan;
bool RobosenseDriver::init() {
bool RobosenseDriver::Init() {
if (node_ == nullptr) {
AERROR << "node is nullptr";
return false;
......
......@@ -19,16 +19,19 @@
#include <thread>
#include <vector>
#include "modules/drivers/lidar/proto/config.pb.h"
#include "modules/drivers/lidar/proto/robosense.pb.h"
#include "modules/drivers/lidar/proto/robosense_config.pb.h"
#include "modules/drivers/proto/pointcloud.pb.h"
#include "modules/drivers/lidar/robosense/proto/config.pb.h"
#include "modules/drivers/lidar/robosense/proto/robosense.pb.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/common/driver_factory/driver_base.h"
#include "modules/drivers/lidar/robosense/decoder/decoder_16.hpp"
#include "modules/drivers/lidar/robosense/decoder/decoder_factory.hpp"
#include "modules/drivers/lidar/robosense/driver/utility.h"
#include "modules/drivers/lidar/robosense/input/input.h"
#define PKT_DATA_LENGTH 1248
namespace apollo {
namespace drivers {
namespace robosense {
......@@ -38,12 +41,15 @@ struct alignas(16) LidarPacketMsg {
std::array<uint8_t, PKT_DATA_LENGTH> packet{}; ///< lidar single packet
};
class RobosenseDriver {
class RobosenseDriver : public lidar::LidarDriver {
public:
RobosenseDriver(const std::shared_ptr<cyber::Node> &node,
const ::apollo::drivers::lidar::config &config)
: node_(node), conf_(config.robosense()) {}
RobosenseDriver(const std::shared_ptr<cyber::Node> &node, const Config &conf)
: node_(node), conf_(conf) {}
~RobosenseDriver() { stop(); }
bool init();
bool Init() override;
private:
void getPackets();
......
......@@ -19,8 +19,6 @@
#include <string>
#include <thread>
#include "modules/drivers/lidar/robosense/proto/config.pb.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/robosense/driver/driver.h"
......@@ -39,7 +37,7 @@ class RobosenseComponent : public Component<> {
return false;
}
driver_.reset(new RobosenseDriver(node_, conf_));
if (!driver_->init()) {
if (!driver_->Init()) {
AERROR << "driver init error";
return false;
}
......
load("//tools:cpplint.bzl", "cpplint")
load("@rules_cc//cc:defs.bzl", "cc_library")
package(default_visibility = ["//visibility:public"])
ROBOSENSE_COPTS = ['-DMODULE_NAME=\\"robosense\\"']
cc_library(
name = "input",
srcs = ["input.cc"],
hdrs = ["input.h"],
copts = ROBOSENSE_COPTS,
)
cpplint()
load("//tools:cpplint.bzl", "cpplint")
load("@rules_proto//proto:defs.bzl", "proto_library")
load("@rules_cc//cc:defs.bzl", "cc_library", "cc_proto_library")
package(default_visibility = ["//visibility:public"])
cc_library(
name = "robosense_proto",
deps = [
":sensor_robosense_proto",
],
)
cc_proto_library(
name = "sensor_robosense_proto",
deps = [
":robosense_proto_lib",
],
)
proto_library(
name = "robosense_proto_lib",
srcs = [
"config.proto",
"robosense.proto",
],
deps = [
"//modules/common/proto:header_proto",
],
)
cpplint()
......@@ -19,8 +19,8 @@ cc_library(
"//cyber",
"//modules/common/adapters:adapter_gflags",
"//modules/common/latency_recorder",
"//modules/drivers/lidar/proto:velodyne_cc_proto",
"//modules/drivers/lidar/velodyne/compensator:compensator_lib",
"//modules/drivers/lidar/velodyne/proto:velodyne_cc_proto",
],
)
......@@ -30,8 +30,8 @@ cc_library(
hdrs = ["compensator.h"],
copts = ['-DMODULE_NAME=\\"velodyne\\"'],
deps = [
"//modules/drivers/lidar/proto:velodyne_config_cc_proto",
"//modules/drivers/proto:pointcloud_cc_proto",
"//modules/drivers/lidar/velodyne/proto:config_cc_proto",
"//modules/transform:buffer",
"@eigen",
],
......
......@@ -24,11 +24,12 @@
// Eigen 3.3.7: #define ALIVE (0)
// fastrtps: enum ChangeKind_t { ALIVE, ... };
#if defined(ALIVE)
# undef ALIVE
#undef ALIVE
#endif
#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
#include "modules/drivers/proto/pointcloud.pb.h"
#include "modules/drivers/lidar/velodyne/proto/config.pb.h"
#include "modules/transform/buffer.h"
namespace apollo {
......
......@@ -21,7 +21,7 @@
#include "modules/common/adapters/adapter_gflags.h"
#include "modules/common/latency_recorder/latency_recorder.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
#include "modules/drivers/lidar/proto/velodyne.pb.h"
using apollo::cyber::Time;
......@@ -37,7 +37,6 @@ bool CompensatorComponent::Init() {
}
writer_ = node_->CreateWriter<PointCloud>(config.output_channel());
compensator_.reset(new Compensator(config));
compensator_pool_.reset(new CCObjectPool<PointCloud>(pool_size_));
compensator_pool_->ConstructAll();
......
......@@ -6,7 +6,7 @@ module_config {
class_name : "VelodyneDriverComponent"
config {
name : "velodyne_driver"
config_file_path : "/apollo/modules/drivers/lidar/velodyne/conf/velodyne16_conf.pb.txt"
config_file_path : "/apollo/modules/drivers/lidar/velodyne/conf/velodyne16_front_center_conf.pb.txt"
}
}
}
......@@ -18,7 +18,7 @@ module_config {
class_name : "VelodyneConvertComponent"
config {
name : "velodyne_convert"
config_file_path : "/apollo/modules/drivers/lidar/velodyne/conf/velodyne16_conf.pb.txt"
config_file_path : "/apollo/modules/drivers/lidar/velodyne/conf/velodyne16_front_center_conf.pb.txt"
readers {channel: "/apollo/sensor/lidar16/Scan"}
}
}
......
......@@ -38,8 +38,10 @@ cc_library(
copts = ['-DMODULE_NAME=\\"velodyne\\"'],
deps = [
"//cyber",
"//modules/common/util",
"//modules/drivers/lidar/velodyne/proto:config_cc_proto",
"//modules/common/util:message_util",
"//modules/drivers/lidar/common/driver_factory:driver_base",
"//modules/drivers/lidar/proto:config",
"//modules/drivers/lidar/proto:velodyne_config_cc_proto",
],
)
......
......@@ -22,8 +22,7 @@
#include <thread>
#include "cyber/cyber.h"
#include "modules/drivers/lidar/velodyne/proto/config.pb.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
#include "modules/common/util/message_util.h"
namespace apollo {
namespace drivers {
......@@ -32,12 +31,15 @@ namespace velodyne {
uint64_t VelodyneDriver::sync_counter = 0;
VelodyneDriver::~VelodyneDriver() {
if (poll_thread_.joinable()) {
poll_thread_.join();
}
if (positioning_thread_.joinable()) {
positioning_thread_.join();
}
}
void VelodyneDriver::Init() {
bool VelodyneDriver::Init() {
double frequency = (config_.rpm() / 60.0); // expected Hz rate
// default number of packets for each scan is a single revolution
......@@ -48,6 +50,7 @@ void VelodyneDriver::Init() {
// open Velodyne input device
input_.reset(new SocketInput());
writer_ = node_->CreateWriter<VelodyneScan>(config_.scan_channel());
positioning_input_.reset(new SocketInput());
input_->init(config_.firing_data_port());
positioning_input_->init(config_.positioning_data_port());
......@@ -55,6 +58,8 @@ void VelodyneDriver::Init() {
// raw data output topic
positioning_thread_ =
std::thread(&VelodyneDriver::PollPositioningPacket, this);
poll_thread_ = std::thread(&VelodyneDriver::DevicePoll, this);
return true;
}
void VelodyneDriver::SetBaseTimeFromNmeaTime(NMEATimePtr nmea_time,
......@@ -225,7 +230,8 @@ void VelodyneDriver::UpdateGpsTopHour(uint32_t current_time) {
last_gps_time_ = current_time;
}
VelodyneDriver* VelodyneDriverFactory::CreateDriver(const Config& config) {
VelodyneDriver* VelodyneDriverFactory::CreateDriver(
const std::shared_ptr<::apollo::cyber::Node>& node, const Config& config) {
auto new_config = config;
if (new_config.prefix_angle() > 35900 || new_config.prefix_angle() < 100) {
AWARN << "invalid prefix angle, prefix_angle must be between 100 and 35900";
......@@ -238,37 +244,37 @@ VelodyneDriver* VelodyneDriverFactory::CreateDriver(const Config& config) {
VelodyneDriver* driver = nullptr;
switch (config.model()) {
case HDL64E_S2: {
driver = new Velodyne64Driver(config);
driver = new Velodyne64Driver(node, config);
driver->SetPacketRate(PACKET_RATE_HDL64E_S2);
break;
}
case HDL64E_S3S: {
driver = new Velodyne64Driver(config);
driver = new Velodyne64Driver(node, config);
driver->SetPacketRate(PACKET_RATE_HDL64E_S3S);
break;
}
case HDL64E_S3D: {
driver = new Velodyne64Driver(config);
driver = new Velodyne64Driver(node, config);
driver->SetPacketRate(PACKET_RATE_HDL64E_S3D);
break;
}
case HDL32E: {
driver = new VelodyneDriver(config);
driver = new VelodyneDriver(node, config);
driver->SetPacketRate(PACKET_RATE_HDL32E);
break;
}
case VLP32C: {
driver = new VelodyneDriver(config);
driver = new VelodyneDriver(node, config);
driver->SetPacketRate(PACKET_RATE_VLP32C);
break;
}
case VLP16: {
driver = new VelodyneDriver(config);
driver = new VelodyneDriver(node, config);
driver->SetPacketRate(PACKET_RATE_VLP16);
break;
}
case VLS128: {
driver = new VelodyneDriver(config);
driver = new VelodyneDriver(node, config);
driver->SetPacketRate(PACKET_RATE_VLS128);
break;
}
......@@ -280,6 +286,20 @@ VelodyneDriver* VelodyneDriverFactory::CreateDriver(const Config& config) {
return driver;
}
void VelodyneDriver::DevicePoll() {
while (!apollo::cyber::IsShutdown()) {
// poll device until end of file
std::shared_ptr<VelodyneScan> scan = std::make_shared<VelodyneScan>();
bool ret = Poll(scan);
if (ret) {
apollo::common::util::FillHeader("velodyne", scan.get());
writer_->Write(scan);
} else {
AWARN << "device poll failed";
}
}
}
} // namespace velodyne
} // namespace drivers
} // namespace apollo
......@@ -19,9 +19,12 @@
#include <memory>
#include <string>
#include "modules/drivers/lidar/proto/config.pb.h"
#include "modules/drivers/lidar/proto/velodyne.pb.h"
#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
#include "modules/drivers/lidar/common/driver_factory/driver_base.h"
#include "modules/drivers/lidar/velodyne/driver/socket_input.h"
#include "modules/drivers/lidar/velodyne/proto/config.pb.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
namespace apollo {
namespace drivers {
......@@ -38,18 +41,27 @@ constexpr double PACKET_RATE_HDL64E_S3D = 5789;
constexpr double PACKET_RATE_VLS128 = 6250.0;
constexpr double PACKET_RATE_VLP32C = 1507.0;
class VelodyneDriver {
class VelodyneDriver : public lidar::LidarDriver {
public:
VelodyneDriver() {}
explicit VelodyneDriver(const Config &config) : config_(config) {}
VelodyneDriver(const std::shared_ptr<cyber::Node> &node,
const Config &config)
: config_(config) {
node_ = node;
}
virtual ~VelodyneDriver();
virtual bool Poll(const std::shared_ptr<VelodyneScan> &scan);
virtual void Init();
bool Init() override;
virtual void PollPositioningPacket();
void SetPacketRate(const double packet_rate) { packet_rate_ = packet_rate; }
void DevicePoll();
protected:
std::thread poll_thread_;
Config config_;
std::shared_ptr<apollo::cyber::Writer<VelodyneScan>> writer_;
std::unique_ptr<Input> input_ = nullptr;
std::unique_ptr<Input> positioning_input_ = nullptr;
std::string topic_;
......@@ -61,7 +73,6 @@ class VelodyneDriver {
static uint64_t sync_counter;
std::thread positioning_thread_;
virtual int PollStandard(std::shared_ptr<VelodyneScan> scan);
bool SetBaseTime();
void SetBaseTimeFromNmeaTime(NMEATimePtr nmea_time, uint64_t *basetime);
......@@ -71,10 +82,16 @@ class VelodyneDriver {
class Velodyne64Driver : public VelodyneDriver {
public:
explicit Velodyne64Driver(const Config &config) : VelodyneDriver(config) {}
~Velodyne64Driver() {}
void Init() override;
Velodyne64Driver(const std::shared_ptr<cyber::Node> &node,
const Config &config) {
node_ = node;
config_ = config;
}
~Velodyne64Driver();
bool Init() override;
bool Poll(const std::shared_ptr<VelodyneScan> &scan) override;
void DevicePoll();
private:
bool CheckAngle(const VelodynePacket &packet);
......@@ -83,7 +100,8 @@ class Velodyne64Driver : public VelodyneDriver {
class VelodyneDriverFactory {
public:
static VelodyneDriver *CreateDriver(const Config &config);
static VelodyneDriver *CreateDriver(
const std::shared_ptr<::apollo::cyber::Node> &node, const Config &config);
};
} // namespace velodyne
......
......@@ -18,14 +18,20 @@
#include <ctime>
#include <string>
#include "modules/common/util/message_util.h"
#include "modules/drivers/lidar/velodyne/driver/driver.h"
// #include "ros/ros.h"
namespace apollo {
namespace drivers {
namespace velodyne {
Velodyne64Driver::~Velodyne64Driver() {
if (poll_thread_.joinable()) {
poll_thread_.join();
}
}
void Velodyne64Driver::Init() {
bool Velodyne64Driver::Init() {
const double frequency = config_.rpm() / 60.0; // expected Hz rate
// default number of packets for each scan is a single revolution
......@@ -35,6 +41,14 @@ void Velodyne64Driver::Init() {
input_.reset(new SocketInput());
input_->init(config_.firing_data_port());
if (node_ == NULL) {
AERROR << "node is NULL";
return false;
}
writer_ = node_->CreateWriter<VelodyneScan>(config_.scan_channel());
poll_thread_ = std::thread(&Velodyne64Driver::DevicePoll, this);
return true;
}
/** poll the device
......@@ -116,6 +130,22 @@ int Velodyne64Driver::PollStandardSync(std::shared_ptr<VelodyneScan> scan) {
return 0;
}
void Velodyne64Driver::DevicePoll() {
while (!apollo::cyber::IsShutdown()) {
// poll device until end of file
std::shared_ptr<VelodyneScan> scan = std::make_shared<VelodyneScan>();
bool ret = Poll(scan);
if (ret) {
apollo::common::util::FillHeader("velodyne", scan.get());
writer_->Write(scan);
} else {
AWARN << "device poll failed";
}
}
AERROR << "CompVelodyneDriver thread exit";
}
} // namespace velodyne
} // namespace drivers
} // namespace apollo
......@@ -23,7 +23,7 @@
#include "cyber/cyber.h"
// #include "velodyne_msgs/VelodyneScanUnified.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
#include "modules/drivers/lidar/proto/velodyne.pb.h"
namespace apollo {
namespace drivers {
......
......@@ -14,14 +14,14 @@
* limitations under the License.
*****************************************************************************/
#include "modules/drivers/lidar/velodyne/driver/velodyne_driver_component.h"
#include <memory>
#include <string>
#include <thread>
#include "cyber/cyber.h"
#include "modules/common/util/message_util.h"
#include "modules/drivers/lidar/velodyne/driver/velodyne_driver_component.h"
namespace apollo {
namespace drivers {
......@@ -35,8 +35,10 @@ bool VelodyneDriverComponent::Init() {
}
AINFO << "Velodyne config: " << velodyne_config.DebugString();
// start the driver
writer_ = node_->CreateWriter<VelodyneScan>(velodyne_config.scan_channel());
VelodyneDriver *driver = VelodyneDriverFactory::CreateDriver(velodyne_config);
std::shared_ptr<::apollo::cyber::Node> node =
apollo::cyber::CreateNode("lidar_drivers");
VelodyneDriver *driver =
VelodyneDriverFactory::CreateDriver(node, velodyne_config);
if (driver == nullptr) {
return false;
}
......@@ -44,31 +46,9 @@ bool VelodyneDriverComponent::Init() {
dvr_->Init();
// spawn device poll thread
runing_ = true;
device_thread_ = std::shared_ptr<std::thread>(
new std::thread(std::bind(&VelodyneDriverComponent::device_poll, this)));
device_thread_->detach();
return true;
}
/** @brief Device poll thread main loop. */
void VelodyneDriverComponent::device_poll() {
while (!apollo::cyber::IsShutdown()) {
// poll device until end of file
std::shared_ptr<VelodyneScan> scan = std::make_shared<VelodyneScan>();
bool ret = dvr_->Poll(scan);
if (ret) {
common::util::FillHeader("velodyne", scan.get());
writer_->Write(scan);
} else {
AWARN << "device poll failed";
}
}
AERROR << "CompVelodyneDriver thread exit";
runing_ = false;
}
} // namespace velodyne
} // namespace drivers
} // namespace apollo
......@@ -19,11 +19,11 @@
#include <string>
#include <thread>
#include "cyber/cyber.h"
#include "modules/drivers/lidar/proto/velodyne.pb.h"
#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/velodyne/driver/driver.h"
#include "modules/drivers/lidar/velodyne/proto/config.pb.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
namespace apollo {
namespace drivers {
......@@ -36,20 +36,13 @@ using apollo::drivers::velodyne::VelodyneScan;
class VelodyneDriverComponent : public Component<> {
public:
~VelodyneDriverComponent() {
if (device_thread_->joinable()) {
device_thread_->join();
}
}
~VelodyneDriverComponent() {}
bool Init() override;
private:
void device_poll();
volatile bool runing_; ///< device thread is running
uint32_t seq_ = 0;
std::shared_ptr<std::thread> device_thread_;
std::shared_ptr<VelodyneDriver> dvr_; ///< driver implementation class
std::shared_ptr<apollo::cyber::Writer<VelodyneScan>> writer_;
};
CYBER_REGISTER_COMPONENT(VelodyneDriverComponent)
......
......@@ -17,8 +17,8 @@ cc_library(
copts = ['-DMODULE_NAME=\\"velodyne\\"'],
deps = [
"//cyber",
"//modules/drivers/lidar/proto:velodyne_config_cc_proto",
"//modules/drivers/proto:pointcloud_cc_proto",
"//modules/drivers/lidar/velodyne/proto:config_cc_proto",
"//modules/transform:buffer",
"@eigen",
],
......
......@@ -25,12 +25,13 @@
// Eigen 3.3.7: #define ALIVE (0)
// fastrtps: enum ChangeKind_t { ALIVE, ... };
#if defined(ALIVE)
# undef ALIVE
#undef ALIVE
#endif
#include "cyber/cyber.h"
#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
#include "modules/drivers/proto/pointcloud.pb.h"
#include "modules/drivers/lidar/velodyne/proto/config.pb.h"
#include "cyber/cyber.h"
#include "modules/transform/buffer.h"
namespace apollo {
......
......@@ -45,7 +45,7 @@ cc_library(
copts = ['-DMODULE_NAME=\\"velodyne\\"'],
deps = [
"//cyber",
"//modules/drivers/lidar/velodyne/proto:config_cc_proto",
"//modules/drivers/lidar/proto:velodyne_config_cc_proto",
"//modules/drivers/proto:pointcloud_cc_proto",
"@boost",
"@com_github_jbeder_yaml_cpp//:yaml-cpp",
......
......@@ -21,8 +21,8 @@
#include "modules/drivers/proto/pointcloud.pb.h"
#include "modules/drivers/lidar/velodyne/parser/velodyne_parser.h"
#include "modules/drivers/lidar/velodyne/proto/config.pb.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
#include "modules/drivers/lidar/proto/velodyne.pb.h"
namespace apollo {
namespace drivers {
......
......@@ -20,10 +20,10 @@
#include <string>
#include <vector>
#include "cyber/cyber.h"
#include "modules/drivers/lidar/proto/velodyne.pb.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/velodyne/parser/calibration.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
namespace apollo {
namespace drivers {
......
......@@ -21,12 +21,12 @@
#include <string>
#include <thread>
#include "modules/drivers/lidar/proto/velodyne.pb.h"
#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
#include "cyber/base/concurrent_object_pool.h"
#include "cyber/cyber.h"
#include "modules/drivers/lidar/velodyne/parser/convert.h"
#include "modules/drivers/lidar/velodyne/proto/config.pb.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
namespace apollo {
namespace drivers {
......
......@@ -59,12 +59,13 @@
#include <boost/format.hpp>
#include "modules/drivers/lidar/proto/velodyne.pb.h"
#include "modules/drivers/lidar/proto/velodyne_config.pb.h"
#include "modules/drivers/proto/pointcloud.pb.h"
#include "modules/drivers/lidar/velodyne/parser/calibration.h"
#include "modules/drivers/lidar/velodyne/parser/const_variables.h"
#include "modules/drivers/lidar/velodyne/parser/online_calibration.h"
#include "modules/drivers/lidar/velodyne/proto/config.pb.h"
#include "modules/drivers/lidar/velodyne/proto/velodyne.pb.h"
namespace apollo {
namespace drivers {
......
## Auto generated by `proto_build_generator.py`
load("@rules_proto//proto:defs.bzl", "proto_library")
load("@rules_cc//cc:defs.bzl", "cc_proto_library")
load("//tools:python_rules.bzl", "py_proto_library")
package(default_visibility = ["//visibility:public"])
cc_proto_library(
name = "velodyne_cc_proto",
deps = [
":velodyne_proto",
],
)
proto_library(
name = "velodyne_proto",
srcs = ["velodyne.proto"],
deps = [
"//modules/common/proto:header_proto",
],
)
py_proto_library(
name = "velodyne_py_pb2",
deps = [
":velodyne_proto",
"//modules/common/proto:header_py_pb2",
],
)
cc_proto_library(
name = "config_cc_proto",
deps = [
":config_proto",
],
)
proto_library(
name = "config_proto",
srcs = ["config.proto"],
deps = [
":velodyne_proto",
],
)
py_proto_library(
name = "config_py_pb2",
deps = [
":config_proto",
":velodyne_py_pb2",
],
)
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册