提交 86282bc0 编写于 作者: fengqikai1414's avatar fengqikai1414 提交者: Dengchengliang

velodyne: use transform api

上级 f2d5490a
......@@ -81,6 +81,7 @@ cc_library(
deps = [
"//modules/drivers/velodyne/proto:velodyne_proto",
"//modules/drivers/proto:sensor_proto",
"//modules/transform:tf2_buffer_lib",
"//framework:cybertron",
"@eigen",
],
......
......@@ -40,7 +40,7 @@ bool Compensator::query_pose_affine_from_tf2(
return false;
}
adu::common::TransformStamped stamped_transform;
apollo::transform::TransformStamped stamped_transform;
try {
stamped_transform =
......
......@@ -21,9 +21,7 @@
#include <memory>
#include <string>
#include "cybertron/cybertron.h"
#include "cybertron/tf2_cybertron/transform_broadcaster.h"
#include "cybertron/tf2_cybertron/buffer.h"
#include "modules/transform/buffer.h"
#include "modules/drivers/proto/pointcloud.pb.h"
#include "modules/drivers/velodyne/parser/const_variables.h"
......@@ -33,7 +31,7 @@ namespace apollo {
namespace drivers {
namespace velodyne {
using apollo::cybertron::tf2_cybertron::Buffer;
using apollo::transform::Buffer;
using apollo::drivers::PointCloud;
using apollo::drivers::velodyne::config::Config;
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册