Rename cartographer_grpc:: namespace as cartographer:☁️:. (#955)
[Code structure RFC](e11bca586f/text/0000-code-structure.md
)
also
`cartographer_grpc::mapping::` -> `cartographer:☁️:`.
`cartographer_grpc::sensor::` -> `cartographer:☁️:`.
master
parent
b79e5b8e29
commit
61552314a0
|
@ -27,33 +27,31 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
namespace mapping {
|
namespace cloud {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
using ::cartographer::common::make_unique;
|
using common::make_unique;
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
|
|
||||||
MapBuilderStub::MapBuilderStub(const std::string& server_address)
|
MapBuilderStub::MapBuilderStub(const std::string& server_address)
|
||||||
: client_channel_(grpc::CreateChannel(server_address,
|
: client_channel_(::grpc::CreateChannel(
|
||||||
grpc::InsecureChannelCredentials())),
|
server_address, ::grpc::InsecureChannelCredentials())),
|
||||||
pose_graph_stub_(make_unique<PoseGraphStub>(client_channel_)) {}
|
pose_graph_stub_(make_unique<PoseGraphStub>(client_channel_)) {}
|
||||||
|
|
||||||
int MapBuilderStub::AddTrajectoryBuilder(
|
int MapBuilderStub::AddTrajectoryBuilder(
|
||||||
const std::set<SensorId>& expected_sensor_ids,
|
const std::set<SensorId>& expected_sensor_ids,
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptions&
|
const mapping::proto::TrajectoryBuilderOptions& trajectory_options,
|
||||||
trajectory_options,
|
|
||||||
LocalSlamResultCallback local_slam_result_callback) {
|
LocalSlamResultCallback local_slam_result_callback) {
|
||||||
proto::AddTrajectoryRequest request;
|
proto::AddTrajectoryRequest request;
|
||||||
*request.mutable_trajectory_builder_options() = trajectory_options;
|
*request.mutable_trajectory_builder_options() = trajectory_options;
|
||||||
for (const auto& sensor_id : expected_sensor_ids) {
|
for (const auto& sensor_id : expected_sensor_ids) {
|
||||||
*request.add_expected_sensor_ids() = sensor::ToProto(sensor_id);
|
*request.add_expected_sensor_ids() = cloud::ToProto(sensor_id);
|
||||||
}
|
}
|
||||||
framework::Client<handlers::AddTrajectoryHandler> client(
|
framework::Client<handlers::AddTrajectoryHandler> client(
|
||||||
client_channel_,
|
client_channel_, framework::CreateLimitedBackoffStrategy(
|
||||||
framework::CreateLimitedBackoffStrategy(
|
common::FromMilliseconds(100), 2.f, 5));
|
||||||
cartographer::common::FromMilliseconds(100), 2.f, 5));
|
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
|
|
||||||
// Construct trajectory builder stub.
|
// Construct trajectory builder stub.
|
||||||
|
@ -67,13 +65,13 @@ int MapBuilderStub::AddTrajectoryBuilder(
|
||||||
}
|
}
|
||||||
|
|
||||||
int MapBuilderStub::AddTrajectoryForDeserialization(
|
int MapBuilderStub::AddTrajectoryForDeserialization(
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptionsWithSensorIds&
|
const mapping::proto::TrajectoryBuilderOptionsWithSensorIds&
|
||||||
options_with_sensor_ids_proto) {
|
options_with_sensor_ids_proto) {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::TrajectoryBuilderInterface*
|
mapping::TrajectoryBuilderInterface* MapBuilderStub::GetTrajectoryBuilder(
|
||||||
MapBuilderStub::GetTrajectoryBuilder(int trajectory_id) const {
|
int trajectory_id) const {
|
||||||
return trajectory_builder_stubs_.at(trajectory_id).get();
|
return trajectory_builder_stubs_.at(trajectory_id).get();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -86,9 +84,8 @@ void MapBuilderStub::FinishTrajectory(int trajectory_id) {
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string MapBuilderStub::SubmapToProto(
|
std::string MapBuilderStub::SubmapToProto(
|
||||||
const cartographer::mapping::SubmapId& submap_id,
|
const mapping::SubmapId& submap_id,
|
||||||
cartographer::mapping::proto::SubmapQuery::Response*
|
mapping::proto::SubmapQuery::Response* submap_query_response) {
|
||||||
submap_query_response) {
|
|
||||||
proto::GetSubmapRequest request;
|
proto::GetSubmapRequest request;
|
||||||
submap_id.ToProto(request.mutable_submap_id());
|
submap_id.ToProto(request.mutable_submap_id());
|
||||||
framework::Client<handlers::GetSubmapHandler> client(client_channel_);
|
framework::Client<handlers::GetSubmapHandler> client(client_channel_);
|
||||||
|
@ -97,8 +94,7 @@ std::string MapBuilderStub::SubmapToProto(
|
||||||
return client.response().error_msg();
|
return client.response().error_msg();
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilderStub::SerializeState(
|
void MapBuilderStub::SerializeState(io::ProtoStreamWriterInterface* writer) {
|
||||||
cartographer::io::ProtoStreamWriterInterface* writer) {
|
|
||||||
google::protobuf::Empty request;
|
google::protobuf::Empty request;
|
||||||
framework::Client<handlers::WriteStateHandler> client(client_channel_);
|
framework::Client<handlers::WriteStateHandler> client(client_channel_);
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
|
@ -122,9 +118,8 @@ void MapBuilderStub::SerializeState(
|
||||||
CHECK(writer->Close());
|
CHECK(writer->Close());
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilderStub::LoadState(
|
void MapBuilderStub::LoadState(io::ProtoStreamReaderInterface* reader,
|
||||||
cartographer::io::ProtoStreamReaderInterface* reader,
|
const bool load_frozen_state) {
|
||||||
const bool load_frozen_state) {
|
|
||||||
if (!load_frozen_state) {
|
if (!load_frozen_state) {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
@ -156,15 +151,14 @@ int MapBuilderStub::num_trajectory_builders() const {
|
||||||
return trajectory_builder_stubs_.size();
|
return trajectory_builder_stubs_.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::PoseGraphInterface* MapBuilderStub::pose_graph() {
|
mapping::PoseGraphInterface* MapBuilderStub::pose_graph() {
|
||||||
return pose_graph_stub_.get();
|
return pose_graph_stub_.get();
|
||||||
}
|
}
|
||||||
|
|
||||||
const std::vector<
|
const std::vector<mapping::proto::TrajectoryBuilderOptionsWithSensorIds>&
|
||||||
cartographer::mapping::proto::TrajectoryBuilderOptionsWithSensorIds>&
|
|
||||||
MapBuilderStub::GetAllTrajectoryBuilderOptions() const {
|
MapBuilderStub::GetAllTrajectoryBuilderOptions() const {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace mapping
|
} // namespace cloud
|
||||||
} // namespace cartographer_grpc
|
} // namespace cartographer
|
||||||
|
|
|
@ -24,10 +24,10 @@
|
||||||
#include "cartographer/mapping/trajectory_builder_interface.h"
|
#include "cartographer/mapping/trajectory_builder_interface.h"
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
namespace mapping {
|
namespace cloud {
|
||||||
|
|
||||||
class MapBuilderStub : public cartographer::mapping::MapBuilderInterface {
|
class MapBuilderStub : public mapping::MapBuilderInterface {
|
||||||
public:
|
public:
|
||||||
MapBuilderStub(const std::string& server_address);
|
MapBuilderStub(const std::string& server_address);
|
||||||
|
|
||||||
|
@ -36,37 +36,33 @@ class MapBuilderStub : public cartographer::mapping::MapBuilderInterface {
|
||||||
|
|
||||||
int AddTrajectoryBuilder(
|
int AddTrajectoryBuilder(
|
||||||
const std::set<SensorId>& expected_sensor_ids,
|
const std::set<SensorId>& expected_sensor_ids,
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptions&
|
const mapping::proto::TrajectoryBuilderOptions& trajectory_options,
|
||||||
trajectory_options,
|
|
||||||
LocalSlamResultCallback local_slam_result_callback) override;
|
LocalSlamResultCallback local_slam_result_callback) override;
|
||||||
int AddTrajectoryForDeserialization(
|
int AddTrajectoryForDeserialization(
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptionsWithSensorIds&
|
const mapping::proto::TrajectoryBuilderOptionsWithSensorIds&
|
||||||
options_with_sensor_ids_proto) override;
|
options_with_sensor_ids_proto) override;
|
||||||
cartographer::mapping::TrajectoryBuilderInterface* GetTrajectoryBuilder(
|
mapping::TrajectoryBuilderInterface* GetTrajectoryBuilder(
|
||||||
int trajectory_id) const override;
|
int trajectory_id) const override;
|
||||||
void FinishTrajectory(int trajectory_id) override;
|
void FinishTrajectory(int trajectory_id) override;
|
||||||
std::string SubmapToProto(
|
std::string SubmapToProto(
|
||||||
const cartographer::mapping::SubmapId& submap_id,
|
const mapping::SubmapId& submap_id,
|
||||||
cartographer::mapping::proto::SubmapQuery::Response* response) override;
|
mapping::proto::SubmapQuery::Response* response) override;
|
||||||
void SerializeState(
|
void SerializeState(io::ProtoStreamWriterInterface* writer) override;
|
||||||
cartographer::io::ProtoStreamWriterInterface* writer) override;
|
void LoadState(io::ProtoStreamReaderInterface* reader,
|
||||||
void LoadState(cartographer::io::ProtoStreamReaderInterface* reader,
|
|
||||||
bool load_frozen_state) override;
|
bool load_frozen_state) override;
|
||||||
int num_trajectory_builders() const override;
|
int num_trajectory_builders() const override;
|
||||||
cartographer::mapping::PoseGraphInterface* pose_graph() override;
|
mapping::PoseGraphInterface* pose_graph() override;
|
||||||
const std::vector<
|
const std::vector<mapping::proto::TrajectoryBuilderOptionsWithSensorIds>&
|
||||||
cartographer::mapping::proto::TrajectoryBuilderOptionsWithSensorIds>&
|
|
||||||
GetAllTrajectoryBuilderOptions() const override;
|
GetAllTrajectoryBuilderOptions() const override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
std::shared_ptr<grpc::Channel> client_channel_;
|
std::shared_ptr<::grpc::Channel> client_channel_;
|
||||||
std::unique_ptr<cartographer::mapping::PoseGraphInterface> pose_graph_stub_;
|
std::unique_ptr<mapping::PoseGraphInterface> pose_graph_stub_;
|
||||||
std::map<int,
|
std::map<int, std::unique_ptr<mapping::TrajectoryBuilderInterface>>
|
||||||
std::unique_ptr<cartographer::mapping::TrajectoryBuilderInterface>>
|
|
||||||
trajectory_builder_stubs_;
|
trajectory_builder_stubs_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace mapping
|
} // namespace cloud
|
||||||
} // namespace cartographer_grpc
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_CLIENT_MAP_BUILDER_STUB_H_
|
#endif // CARTOGRAPHER_GRPC_CLIENT_MAP_BUILDER_STUB_H_
|
||||||
|
|
|
@ -25,10 +25,10 @@
|
||||||
#include "cartographer_grpc/internal/handlers/run_final_optimization_handler.h"
|
#include "cartographer_grpc/internal/handlers/run_final_optimization_handler.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
namespace mapping {
|
namespace cloud {
|
||||||
|
|
||||||
PoseGraphStub::PoseGraphStub(std::shared_ptr<grpc::Channel> client_channel)
|
PoseGraphStub::PoseGraphStub(std::shared_ptr<::grpc::Channel> client_channel)
|
||||||
: client_channel_(client_channel) {}
|
: client_channel_(client_channel) {}
|
||||||
|
|
||||||
void PoseGraphStub::RunFinalOptimization() {
|
void PoseGraphStub::RunFinalOptimization() {
|
||||||
|
@ -38,81 +38,68 @@ void PoseGraphStub::RunFinalOptimization() {
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::MapById<
|
mapping::MapById<mapping::SubmapId, mapping::PoseGraphInterface::SubmapData>
|
||||||
cartographer::mapping::SubmapId,
|
|
||||||
cartographer::mapping::PoseGraphInterface::SubmapData>
|
|
||||||
PoseGraphStub::GetAllSubmapData() {
|
PoseGraphStub::GetAllSubmapData() {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::MapById<
|
mapping::MapById<mapping::SubmapId, mapping::PoseGraphInterface::SubmapPose>
|
||||||
cartographer::mapping::SubmapId,
|
|
||||||
cartographer::mapping::PoseGraphInterface::SubmapPose>
|
|
||||||
PoseGraphStub::GetAllSubmapPoses() {
|
PoseGraphStub::GetAllSubmapPoses() {
|
||||||
google::protobuf::Empty request;
|
google::protobuf::Empty request;
|
||||||
framework::Client<handlers::GetAllSubmapPosesHandler> client(client_channel_);
|
framework::Client<handlers::GetAllSubmapPosesHandler> client(client_channel_);
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
cartographer::mapping::MapById<
|
mapping::MapById<mapping::SubmapId, mapping::PoseGraphInterface::SubmapPose>
|
||||||
cartographer::mapping::SubmapId,
|
|
||||||
cartographer::mapping::PoseGraphInterface::SubmapPose>
|
|
||||||
submap_poses;
|
submap_poses;
|
||||||
for (const auto& submap_pose : client.response().submap_poses()) {
|
for (const auto& submap_pose : client.response().submap_poses()) {
|
||||||
submap_poses.Insert(
|
submap_poses.Insert(
|
||||||
cartographer::mapping::SubmapId{submap_pose.submap_id().trajectory_id(),
|
mapping::SubmapId{submap_pose.submap_id().trajectory_id(),
|
||||||
submap_pose.submap_id().submap_index()},
|
submap_pose.submap_id().submap_index()},
|
||||||
cartographer::mapping::PoseGraphInterface::SubmapPose{
|
mapping::PoseGraphInterface::SubmapPose{
|
||||||
submap_pose.submap_version(),
|
submap_pose.submap_version(),
|
||||||
cartographer::transform::ToRigid3(submap_pose.global_pose())});
|
transform::ToRigid3(submap_pose.global_pose())});
|
||||||
}
|
}
|
||||||
return submap_poses;
|
return submap_poses;
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::transform::Rigid3d PoseGraphStub::GetLocalToGlobalTransform(
|
transform::Rigid3d PoseGraphStub::GetLocalToGlobalTransform(int trajectory_id) {
|
||||||
int trajectory_id) {
|
|
||||||
proto::GetLocalToGlobalTransformRequest request;
|
proto::GetLocalToGlobalTransformRequest request;
|
||||||
request.set_trajectory_id(trajectory_id);
|
request.set_trajectory_id(trajectory_id);
|
||||||
framework::Client<handlers::GetLocalToGlobalTransformHandler> client(
|
framework::Client<handlers::GetLocalToGlobalTransformHandler> client(
|
||||||
client_channel_);
|
client_channel_);
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
return cartographer::transform::ToRigid3(client.response().local_to_global());
|
return transform::ToRigid3(client.response().local_to_global());
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::MapById<cartographer::mapping::NodeId,
|
mapping::MapById<mapping::NodeId, mapping::TrajectoryNode>
|
||||||
cartographer::mapping::TrajectoryNode>
|
|
||||||
PoseGraphStub::GetTrajectoryNodes() {
|
PoseGraphStub::GetTrajectoryNodes() {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::MapById<cartographer::mapping::NodeId,
|
mapping::MapById<mapping::NodeId, mapping::TrajectoryNodePose>
|
||||||
cartographer::mapping::TrajectoryNodePose>
|
|
||||||
PoseGraphStub::GetTrajectoryNodePoses() {
|
PoseGraphStub::GetTrajectoryNodePoses() {
|
||||||
google::protobuf::Empty request;
|
google::protobuf::Empty request;
|
||||||
framework::Client<handlers::GetTrajectoryNodePosesHandler> client(
|
framework::Client<handlers::GetTrajectoryNodePosesHandler> client(
|
||||||
client_channel_);
|
client_channel_);
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
cartographer::mapping::MapById<cartographer::mapping::NodeId,
|
mapping::MapById<mapping::NodeId, mapping::TrajectoryNodePose> node_poses;
|
||||||
cartographer::mapping::TrajectoryNodePose>
|
|
||||||
node_poses;
|
|
||||||
for (const auto& node_pose : client.response().node_poses()) {
|
for (const auto& node_pose : client.response().node_poses()) {
|
||||||
node_poses.Insert(
|
node_poses.Insert(mapping::NodeId{node_pose.node_id().trajectory_id(),
|
||||||
cartographer::mapping::NodeId{node_pose.node_id().trajectory_id(),
|
|
||||||
node_pose.node_id().node_index()},
|
node_pose.node_id().node_index()},
|
||||||
cartographer::mapping::TrajectoryNodePose{
|
mapping::TrajectoryNodePose{
|
||||||
node_pose.has_constant_data(),
|
node_pose.has_constant_data(),
|
||||||
cartographer::transform::ToRigid3(node_pose.global_pose())});
|
transform::ToRigid3(node_pose.global_pose())});
|
||||||
}
|
}
|
||||||
return node_poses;
|
return node_poses;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::map<std::string, cartographer::transform::Rigid3d>
|
std::map<std::string, transform::Rigid3d> PoseGraphStub::GetLandmarkPoses() {
|
||||||
PoseGraphStub::GetLandmarkPoses() {
|
|
||||||
google::protobuf::Empty request;
|
google::protobuf::Empty request;
|
||||||
framework::Client<handlers::GetLandmarkPosesHandler> client(client_channel_);
|
framework::Client<handlers::GetLandmarkPosesHandler> client(client_channel_);
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
std::map<std::string, cartographer::transform::Rigid3d> landmark_poses;
|
std::map<std::string, transform::Rigid3d> landmark_poses;
|
||||||
for (const auto& landmark_pose : client.response().landmark_poses()) {
|
for (const auto& landmark_pose : client.response().landmark_poses()) {
|
||||||
landmark_poses[landmark_pose.landmark_id()] =
|
landmark_poses[landmark_pose.landmark_id()] =
|
||||||
cartographer::transform::ToRigid3(landmark_pose.global_pose());
|
transform::ToRigid3(landmark_pose.global_pose());
|
||||||
}
|
}
|
||||||
return landmark_poses;
|
return landmark_poses;
|
||||||
}
|
}
|
||||||
|
@ -121,22 +108,22 @@ bool PoseGraphStub::IsTrajectoryFinished(int trajectory_id) {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
std::map<int, cartographer::mapping::PoseGraphInterface::TrajectoryData>
|
std::map<int, mapping::PoseGraphInterface::TrajectoryData>
|
||||||
PoseGraphStub::GetTrajectoryData() {
|
PoseGraphStub::GetTrajectoryData() {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
std::vector<cartographer::mapping::PoseGraphInterface::Constraint>
|
std::vector<mapping::PoseGraphInterface::Constraint>
|
||||||
PoseGraphStub::constraints() {
|
PoseGraphStub::constraints() {
|
||||||
google::protobuf::Empty request;
|
google::protobuf::Empty request;
|
||||||
framework::Client<handlers::GetConstraintsHandler> client(client_channel_);
|
framework::Client<handlers::GetConstraintsHandler> client(client_channel_);
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
return cartographer::mapping::FromProto(client.response().constraints());
|
return mapping::FromProto(client.response().constraints());
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::proto::PoseGraph PoseGraphStub::ToProto() {
|
mapping::proto::PoseGraph PoseGraphStub::ToProto() {
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace mapping
|
} // namespace cloud
|
||||||
} // namespace cartographer_grpc
|
} // namespace cartographer
|
||||||
|
|
|
@ -20,42 +20,36 @@
|
||||||
#include "cartographer/mapping/pose_graph_interface.h"
|
#include "cartographer/mapping/pose_graph_interface.h"
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
namespace mapping {
|
namespace cloud {
|
||||||
|
|
||||||
class PoseGraphStub : public cartographer::mapping::PoseGraphInterface {
|
class PoseGraphStub : public ::cartographer::mapping::PoseGraphInterface {
|
||||||
public:
|
public:
|
||||||
PoseGraphStub(std::shared_ptr<grpc::Channel> client_channel);
|
PoseGraphStub(std::shared_ptr<::grpc::Channel> client_channel);
|
||||||
|
|
||||||
PoseGraphStub(const PoseGraphStub&) = delete;
|
PoseGraphStub(const PoseGraphStub&) = delete;
|
||||||
PoseGraphStub& operator=(const PoseGraphStub&) = delete;
|
PoseGraphStub& operator=(const PoseGraphStub&) = delete;
|
||||||
|
|
||||||
void RunFinalOptimization() override;
|
void RunFinalOptimization() override;
|
||||||
cartographer::mapping::MapById<cartographer::mapping::SubmapId, SubmapData>
|
mapping::MapById<mapping::SubmapId, SubmapData> GetAllSubmapData() override;
|
||||||
GetAllSubmapData() override;
|
mapping::MapById<mapping::SubmapId, SubmapPose> GetAllSubmapPoses() override;
|
||||||
cartographer::mapping::MapById<cartographer::mapping::SubmapId, SubmapPose>
|
transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) override;
|
||||||
GetAllSubmapPoses() override;
|
mapping::MapById<mapping::NodeId, mapping::TrajectoryNode>
|
||||||
cartographer::transform::Rigid3d GetLocalToGlobalTransform(
|
|
||||||
int trajectory_id) override;
|
|
||||||
cartographer::mapping::MapById<cartographer::mapping::NodeId,
|
|
||||||
cartographer::mapping::TrajectoryNode>
|
|
||||||
GetTrajectoryNodes() override;
|
GetTrajectoryNodes() override;
|
||||||
cartographer::mapping::MapById<cartographer::mapping::NodeId,
|
mapping::MapById<mapping::NodeId, mapping::TrajectoryNodePose>
|
||||||
cartographer::mapping::TrajectoryNodePose>
|
|
||||||
GetTrajectoryNodePoses() override;
|
GetTrajectoryNodePoses() override;
|
||||||
std::map<std::string, cartographer::transform::Rigid3d> GetLandmarkPoses()
|
std::map<std::string, transform::Rigid3d> GetLandmarkPoses() override;
|
||||||
override;
|
|
||||||
bool IsTrajectoryFinished(int trajectory_id) override;
|
bool IsTrajectoryFinished(int trajectory_id) override;
|
||||||
std::map<int, cartographer::mapping::PoseGraphInterface::TrajectoryData>
|
std::map<int, mapping::PoseGraphInterface::TrajectoryData> GetTrajectoryData()
|
||||||
GetTrajectoryData() override;
|
override;
|
||||||
std::vector<Constraint> constraints() override;
|
std::vector<Constraint> constraints() override;
|
||||||
cartographer::mapping::proto::PoseGraph ToProto() override;
|
mapping::proto::PoseGraph ToProto() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
std::shared_ptr<grpc::Channel> client_channel_;
|
std::shared_ptr<::grpc::Channel> client_channel_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace mapping
|
} // namespace cloud
|
||||||
} // namespace cartographer_grpc
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_CLIENT_POSE_GRAPH_STUB_H_
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_CLIENT_POSE_GRAPH_STUB_H_
|
||||||
|
|
|
@ -21,11 +21,11 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
namespace mapping {
|
namespace cloud {
|
||||||
|
|
||||||
TrajectoryBuilderStub::TrajectoryBuilderStub(
|
TrajectoryBuilderStub::TrajectoryBuilderStub(
|
||||||
std::shared_ptr<grpc::Channel> client_channel, const int trajectory_id,
|
std::shared_ptr<::grpc::Channel> client_channel, const int trajectory_id,
|
||||||
LocalSlamResultCallback local_slam_result_callback)
|
LocalSlamResultCallback local_slam_result_callback)
|
||||||
: client_channel_(client_channel),
|
: client_channel_(client_channel),
|
||||||
trajectory_id_(trajectory_id),
|
trajectory_id_(trajectory_id),
|
||||||
|
@ -36,13 +36,11 @@ TrajectoryBuilderStub::TrajectoryBuilderStub(
|
||||||
receive_local_slam_results_client_.Write(request);
|
receive_local_slam_results_client_.Write(request);
|
||||||
auto* receive_local_slam_results_client_ptr =
|
auto* receive_local_slam_results_client_ptr =
|
||||||
&receive_local_slam_results_client_;
|
&receive_local_slam_results_client_;
|
||||||
receive_local_slam_results_thread_ =
|
receive_local_slam_results_thread_ = common::make_unique<std::thread>(
|
||||||
cartographer::common::make_unique<std::thread>(
|
[receive_local_slam_results_client_ptr, local_slam_result_callback]() {
|
||||||
[receive_local_slam_results_client_ptr,
|
RunLocalSlamResultsReader(receive_local_slam_results_client_ptr,
|
||||||
local_slam_result_callback]() {
|
local_slam_result_callback);
|
||||||
RunLocalSlamResultsReader(receive_local_slam_results_client_ptr,
|
});
|
||||||
local_slam_result_callback);
|
|
||||||
});
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -74,79 +72,72 @@ TrajectoryBuilderStub::~TrajectoryBuilderStub() {
|
||||||
|
|
||||||
void TrajectoryBuilderStub::AddSensorData(
|
void TrajectoryBuilderStub::AddSensorData(
|
||||||
const std::string& sensor_id,
|
const std::string& sensor_id,
|
||||||
const cartographer::sensor::TimedPointCloudData& timed_point_cloud_data) {
|
const sensor::TimedPointCloudData& timed_point_cloud_data) {
|
||||||
if (!add_rangefinder_client_) {
|
if (!add_rangefinder_client_) {
|
||||||
add_rangefinder_client_ = cartographer::common::make_unique<
|
add_rangefinder_client_ = common::make_unique<
|
||||||
framework::Client<handlers::AddRangefinderDataHandler>>(
|
framework::Client<handlers::AddRangefinderDataHandler>>(
|
||||||
client_channel_);
|
client_channel_);
|
||||||
}
|
}
|
||||||
proto::AddRangefinderDataRequest request;
|
proto::AddRangefinderDataRequest request;
|
||||||
sensor::CreateAddRangeFinderDataRequest(
|
CreateAddRangeFinderDataRequest(sensor_id, trajectory_id_,
|
||||||
sensor_id, trajectory_id_,
|
sensor::ToProto(timed_point_cloud_data),
|
||||||
cartographer::sensor::ToProto(timed_point_cloud_data), &request);
|
&request);
|
||||||
add_rangefinder_client_->Write(request);
|
add_rangefinder_client_->Write(request);
|
||||||
}
|
}
|
||||||
|
|
||||||
void TrajectoryBuilderStub::AddSensorData(
|
void TrajectoryBuilderStub::AddSensorData(const std::string& sensor_id,
|
||||||
const std::string& sensor_id,
|
const sensor::ImuData& imu_data) {
|
||||||
const cartographer::sensor::ImuData& imu_data) {
|
|
||||||
if (!add_imu_client_) {
|
if (!add_imu_client_) {
|
||||||
add_imu_client_ = cartographer::common::make_unique<
|
add_imu_client_ =
|
||||||
framework::Client<handlers::AddImuDataHandler>>(client_channel_);
|
common::make_unique<framework::Client<handlers::AddImuDataHandler>>(
|
||||||
|
client_channel_);
|
||||||
}
|
}
|
||||||
proto::AddImuDataRequest request;
|
proto::AddImuDataRequest request;
|
||||||
sensor::CreateAddImuDataRequest(sensor_id, trajectory_id_,
|
CreateAddImuDataRequest(sensor_id, trajectory_id_, sensor::ToProto(imu_data),
|
||||||
cartographer::sensor::ToProto(imu_data),
|
&request);
|
||||||
&request);
|
|
||||||
add_imu_client_->Write(request);
|
add_imu_client_->Write(request);
|
||||||
}
|
}
|
||||||
|
|
||||||
void TrajectoryBuilderStub::AddSensorData(
|
void TrajectoryBuilderStub::AddSensorData(
|
||||||
const std::string& sensor_id,
|
const std::string& sensor_id, const sensor::OdometryData& odometry_data) {
|
||||||
const cartographer::sensor::OdometryData& odometry_data) {
|
|
||||||
if (!add_odometry_client_) {
|
if (!add_odometry_client_) {
|
||||||
add_odometry_client_ = cartographer::common::make_unique<
|
add_odometry_client_ = common::make_unique<
|
||||||
framework::Client<handlers::AddOdometryDataHandler>>(client_channel_);
|
framework::Client<handlers::AddOdometryDataHandler>>(client_channel_);
|
||||||
}
|
}
|
||||||
proto::AddOdometryDataRequest request;
|
proto::AddOdometryDataRequest request;
|
||||||
sensor::CreateAddOdometryDataRequest(
|
CreateAddOdometryDataRequest(sensor_id, trajectory_id_,
|
||||||
sensor_id, trajectory_id_, cartographer::sensor::ToProto(odometry_data),
|
sensor::ToProto(odometry_data), &request);
|
||||||
&request);
|
|
||||||
add_odometry_client_->Write(request);
|
add_odometry_client_->Write(request);
|
||||||
}
|
}
|
||||||
|
|
||||||
void TrajectoryBuilderStub::AddSensorData(
|
void TrajectoryBuilderStub::AddSensorData(
|
||||||
const std::string& sensor_id,
|
const std::string& sensor_id,
|
||||||
const cartographer::sensor::FixedFramePoseData& fixed_frame_pose) {
|
const sensor::FixedFramePoseData& fixed_frame_pose) {
|
||||||
if (!add_fixed_frame_pose_client_) {
|
if (!add_fixed_frame_pose_client_) {
|
||||||
add_fixed_frame_pose_client_ = cartographer::common::make_unique<
|
add_fixed_frame_pose_client_ = common::make_unique<
|
||||||
framework::Client<handlers::AddFixedFramePoseDataHandler>>(
|
framework::Client<handlers::AddFixedFramePoseDataHandler>>(
|
||||||
client_channel_);
|
client_channel_);
|
||||||
}
|
}
|
||||||
proto::AddFixedFramePoseDataRequest request;
|
proto::AddFixedFramePoseDataRequest request;
|
||||||
sensor::CreateAddFixedFramePoseDataRequest(
|
CreateAddFixedFramePoseDataRequest(
|
||||||
sensor_id, trajectory_id_,
|
sensor_id, trajectory_id_, sensor::ToProto(fixed_frame_pose), &request);
|
||||||
cartographer::sensor::ToProto(fixed_frame_pose), &request);
|
|
||||||
add_fixed_frame_pose_client_->Write(request);
|
add_fixed_frame_pose_client_->Write(request);
|
||||||
}
|
}
|
||||||
|
|
||||||
void TrajectoryBuilderStub::AddSensorData(
|
void TrajectoryBuilderStub::AddSensorData(
|
||||||
const std::string& sensor_id,
|
const std::string& sensor_id, const sensor::LandmarkData& landmark_data) {
|
||||||
const cartographer::sensor::LandmarkData& landmark_data) {
|
|
||||||
if (!add_landmark_client_) {
|
if (!add_landmark_client_) {
|
||||||
add_landmark_client_ = cartographer::common::make_unique<
|
add_landmark_client_ = common::make_unique<
|
||||||
framework::Client<handlers::AddLandmarkDataHandler>>(client_channel_);
|
framework::Client<handlers::AddLandmarkDataHandler>>(client_channel_);
|
||||||
}
|
}
|
||||||
proto::AddLandmarkDataRequest request;
|
proto::AddLandmarkDataRequest request;
|
||||||
sensor::CreateAddLandmarkDataRequest(
|
CreateAddLandmarkDataRequest(sensor_id, trajectory_id_,
|
||||||
sensor_id, trajectory_id_, cartographer::sensor::ToProto(landmark_data),
|
sensor::ToProto(landmark_data), &request);
|
||||||
&request);
|
|
||||||
add_landmark_client_->Write(request);
|
add_landmark_client_->Write(request);
|
||||||
}
|
}
|
||||||
|
|
||||||
void TrajectoryBuilderStub::AddLocalSlamResultData(
|
void TrajectoryBuilderStub::AddLocalSlamResultData(
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
std::unique_ptr<mapping::LocalSlamResultData> local_slam_result_data) {
|
||||||
local_slam_result_data) {
|
|
||||||
LOG(FATAL) << "Not implemented";
|
LOG(FATAL) << "Not implemented";
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -156,16 +147,13 @@ void TrajectoryBuilderStub::RunLocalSlamResultsReader(
|
||||||
proto::ReceiveLocalSlamResultsResponse response;
|
proto::ReceiveLocalSlamResultsResponse response;
|
||||||
while (client->Read(&response)) {
|
while (client->Read(&response)) {
|
||||||
int trajectory_id = response.trajectory_id();
|
int trajectory_id = response.trajectory_id();
|
||||||
cartographer::common::Time time =
|
common::Time time = common::FromUniversal(response.timestamp());
|
||||||
cartographer::common::FromUniversal(response.timestamp());
|
transform::Rigid3d local_pose = transform::ToRigid3(response.local_pose());
|
||||||
cartographer::transform::Rigid3d local_pose =
|
sensor::RangeData range_data = sensor::FromProto(response.range_data());
|
||||||
cartographer::transform::ToRigid3(response.local_pose());
|
|
||||||
cartographer::sensor::RangeData range_data =
|
|
||||||
cartographer::sensor::FromProto(response.range_data());
|
|
||||||
auto insertion_result =
|
auto insertion_result =
|
||||||
response.has_insertion_result()
|
response.has_insertion_result()
|
||||||
? cartographer::common::make_unique<InsertionResult>(
|
? common::make_unique<InsertionResult>(
|
||||||
InsertionResult{cartographer::mapping::NodeId{
|
InsertionResult{mapping::NodeId{
|
||||||
response.insertion_result().node_id().trajectory_id(),
|
response.insertion_result().node_id().trajectory_id(),
|
||||||
response.insertion_result().node_id().node_index()}})
|
response.insertion_result().node_id().node_index()}})
|
||||||
: nullptr;
|
: nullptr;
|
||||||
|
@ -175,5 +163,5 @@ void TrajectoryBuilderStub::RunLocalSlamResultsReader(
|
||||||
client->Finish();
|
client->Finish();
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace mapping
|
} // namespace cloud
|
||||||
} // namespace cartographer_grpc
|
} // namespace cartographer
|
||||||
|
|
|
@ -33,36 +33,32 @@
|
||||||
#include "pose_graph_stub.h"
|
#include "pose_graph_stub.h"
|
||||||
#include "trajectory_builder_stub.h"
|
#include "trajectory_builder_stub.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
namespace mapping {
|
namespace cloud {
|
||||||
|
|
||||||
class TrajectoryBuilderStub
|
class TrajectoryBuilderStub : public mapping::TrajectoryBuilderInterface {
|
||||||
: public cartographer::mapping::TrajectoryBuilderInterface {
|
|
||||||
public:
|
public:
|
||||||
TrajectoryBuilderStub(std::shared_ptr<grpc::Channel> client_channel,
|
TrajectoryBuilderStub(std::shared_ptr<::grpc::Channel> client_channel,
|
||||||
const int trajectory_id,
|
const int trajectory_id,
|
||||||
LocalSlamResultCallback local_slam_result_callback);
|
LocalSlamResultCallback local_slam_result_callback);
|
||||||
~TrajectoryBuilderStub() override;
|
~TrajectoryBuilderStub() override;
|
||||||
TrajectoryBuilderStub(const TrajectoryBuilderStub&) = delete;
|
TrajectoryBuilderStub(const TrajectoryBuilderStub&) = delete;
|
||||||
TrajectoryBuilderStub& operator=(const TrajectoryBuilderStub&) = delete;
|
TrajectoryBuilderStub& operator=(const TrajectoryBuilderStub&) = delete;
|
||||||
|
|
||||||
void AddSensorData(const std::string& sensor_id,
|
|
||||||
const cartographer::sensor::TimedPointCloudData&
|
|
||||||
timed_point_cloud_data) override;
|
|
||||||
void AddSensorData(const std::string& sensor_id,
|
|
||||||
const cartographer::sensor::ImuData& imu_data) override;
|
|
||||||
void AddSensorData(
|
void AddSensorData(
|
||||||
const std::string& sensor_id,
|
const std::string& sensor_id,
|
||||||
const cartographer::sensor::OdometryData& odometry_data) override;
|
const sensor::TimedPointCloudData& timed_point_cloud_data) override;
|
||||||
void AddSensorData(const std::string& sensor_id,
|
void AddSensorData(const std::string& sensor_id,
|
||||||
const cartographer::sensor::FixedFramePoseData&
|
const sensor::ImuData& imu_data) override;
|
||||||
fixed_frame_pose) override;
|
void AddSensorData(const std::string& sensor_id,
|
||||||
|
const sensor::OdometryData& odometry_data) override;
|
||||||
void AddSensorData(
|
void AddSensorData(
|
||||||
const std::string& sensor_id,
|
const std::string& sensor_id,
|
||||||
const cartographer::sensor::LandmarkData& landmark_data) override;
|
const sensor::FixedFramePoseData& fixed_frame_pose) override;
|
||||||
void AddLocalSlamResultData(
|
void AddSensorData(const std::string& sensor_id,
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
const sensor::LandmarkData& landmark_data) override;
|
||||||
local_slam_result_data) override;
|
void AddLocalSlamResultData(std::unique_ptr<mapping::LocalSlamResultData>
|
||||||
|
local_slam_result_data) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static void RunLocalSlamResultsReader(
|
static void RunLocalSlamResultsReader(
|
||||||
|
@ -70,7 +66,7 @@ class TrajectoryBuilderStub
|
||||||
client_reader,
|
client_reader,
|
||||||
LocalSlamResultCallback local_slam_result_callback);
|
LocalSlamResultCallback local_slam_result_callback);
|
||||||
|
|
||||||
std::shared_ptr<grpc::Channel> client_channel_;
|
std::shared_ptr<::grpc::Channel> client_channel_;
|
||||||
const int trajectory_id_;
|
const int trajectory_id_;
|
||||||
std::unique_ptr<framework::Client<handlers::AddRangefinderDataHandler>>
|
std::unique_ptr<framework::Client<handlers::AddRangefinderDataHandler>>
|
||||||
add_rangefinder_client_;
|
add_rangefinder_client_;
|
||||||
|
@ -87,7 +83,7 @@ class TrajectoryBuilderStub
|
||||||
std::unique_ptr<std::thread> receive_local_slam_results_thread_;
|
std::unique_ptr<std::thread> receive_local_slam_results_thread_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace mapping
|
} // namespace cloud
|
||||||
} // namespace cartographer_grpc
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_CLIENT_TRAJECTORY_BUILDER_STUB_H_
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_CLIENT_TRAJECTORY_BUILDER_STUB_H_
|
||||||
|
|
|
@ -28,14 +28,15 @@
|
||||||
#include "gmock/gmock.h"
|
#include "gmock/gmock.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
using cartographer::mapping::MapBuilder;
|
using ::cartographer::mapping::MapBuilder;
|
||||||
using cartographer::mapping::MapBuilderInterface;
|
using ::cartographer::mapping::MapBuilderInterface;
|
||||||
using cartographer::mapping::PoseGraphInterface;
|
using ::cartographer::mapping::PoseGraphInterface;
|
||||||
using cartographer::mapping::TrajectoryBuilderInterface;
|
using ::cartographer::mapping::TrajectoryBuilderInterface;
|
||||||
using SensorId = cartographer::mapping::TrajectoryBuilderInterface::SensorId;
|
using ::testing::_;
|
||||||
using testing::_;
|
using SensorId = ::cartographer::mapping::TrajectoryBuilderInterface::SensorId;
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
const SensorId kImuSensorId{SensorId::SensorType::IMU, "imu"};
|
const SensorId kImuSensorId{SensorId::SensorType::IMU, "imu"};
|
||||||
|
@ -58,7 +59,7 @@ class ClientServerTest : public ::testing::Test {
|
||||||
MAP_BUILDER_SERVER.uplink_server_address = ""
|
MAP_BUILDER_SERVER.uplink_server_address = ""
|
||||||
return MAP_BUILDER_SERVER)text";
|
return MAP_BUILDER_SERVER)text";
|
||||||
auto map_builder_server_parameters =
|
auto map_builder_server_parameters =
|
||||||
cartographer::mapping::test::ResolveLuaParameters(kMapBuilderServerLua);
|
mapping::test::ResolveLuaParameters(kMapBuilderServerLua);
|
||||||
map_builder_server_options_ =
|
map_builder_server_options_ =
|
||||||
CreateMapBuilderServerOptions(map_builder_server_parameters.get());
|
CreateMapBuilderServerOptions(map_builder_server_parameters.get());
|
||||||
const std::string kTrajectoryBuilderLua = R"text(
|
const std::string kTrajectoryBuilderLua = R"text(
|
||||||
|
@ -67,18 +68,14 @@ class ClientServerTest : public ::testing::Test {
|
||||||
TRAJECTORY_BUILDER.trajectory_builder_2d.submaps.num_range_data = 4
|
TRAJECTORY_BUILDER.trajectory_builder_2d.submaps.num_range_data = 4
|
||||||
return TRAJECTORY_BUILDER)text";
|
return TRAJECTORY_BUILDER)text";
|
||||||
auto trajectory_builder_parameters =
|
auto trajectory_builder_parameters =
|
||||||
cartographer::mapping::test::ResolveLuaParameters(
|
mapping::test::ResolveLuaParameters(kTrajectoryBuilderLua);
|
||||||
kTrajectoryBuilderLua);
|
trajectory_builder_options_ = mapping::CreateTrajectoryBuilderOptions(
|
||||||
trajectory_builder_options_ =
|
trajectory_builder_parameters.get());
|
||||||
cartographer::mapping::CreateTrajectoryBuilderOptions(
|
|
||||||
trajectory_builder_parameters.get());
|
|
||||||
local_slam_result_callback_ =
|
local_slam_result_callback_ =
|
||||||
[this](
|
[this](
|
||||||
int, cartographer::common::Time,
|
int, common::Time, transform::Rigid3d local_pose, sensor::RangeData,
|
||||||
cartographer::transform::Rigid3d local_pose,
|
std::unique_ptr<
|
||||||
cartographer::sensor::RangeData,
|
const mapping::TrajectoryBuilderInterface::InsertionResult>) {
|
||||||
std::unique_ptr<const cartographer::mapping::
|
|
||||||
TrajectoryBuilderInterface::InsertionResult>) {
|
|
||||||
std::unique_lock<std::mutex> lock(local_slam_result_mutex_);
|
std::unique_lock<std::mutex> lock(local_slam_result_mutex_);
|
||||||
local_slam_result_poses_.push_back(local_pose);
|
local_slam_result_poses_.push_back(local_pose);
|
||||||
lock.unlock();
|
lock.unlock();
|
||||||
|
@ -87,26 +84,25 @@ class ClientServerTest : public ::testing::Test {
|
||||||
}
|
}
|
||||||
|
|
||||||
void InitializeRealServer() {
|
void InitializeRealServer() {
|
||||||
auto map_builder = cartographer::common::make_unique<MapBuilder>(
|
auto map_builder = common::make_unique<MapBuilder>(
|
||||||
map_builder_server_options_.map_builder_options());
|
map_builder_server_options_.map_builder_options());
|
||||||
server_ = cartographer::common::make_unique<MapBuilderServer>(
|
server_ = common::make_unique<MapBuilderServer>(map_builder_server_options_,
|
||||||
map_builder_server_options_, std::move(map_builder));
|
std::move(map_builder));
|
||||||
EXPECT_TRUE(server_ != nullptr);
|
EXPECT_TRUE(server_ != nullptr);
|
||||||
}
|
}
|
||||||
|
|
||||||
void InitializeServerWithMockMapBuilder() {
|
void InitializeServerWithMockMapBuilder() {
|
||||||
auto mock_map_builder =
|
auto mock_map_builder = common::make_unique<testing::MockMapBuilder>();
|
||||||
cartographer::common::make_unique<testing::MockMapBuilder>();
|
|
||||||
mock_map_builder_ = mock_map_builder.get();
|
mock_map_builder_ = mock_map_builder.get();
|
||||||
server_ = cartographer::common::make_unique<MapBuilderServer>(
|
server_ = common::make_unique<MapBuilderServer>(
|
||||||
map_builder_server_options_, std::move(mock_map_builder));
|
map_builder_server_options_, std::move(mock_map_builder));
|
||||||
EXPECT_TRUE(server_ != nullptr);
|
EXPECT_TRUE(server_ != nullptr);
|
||||||
mock_trajectory_builder_ =
|
mock_trajectory_builder_ =
|
||||||
cartographer::common::make_unique<testing::MockTrajectoryBuilder>();
|
common::make_unique<testing::MockTrajectoryBuilder>();
|
||||||
}
|
}
|
||||||
|
|
||||||
void InitializeStub() {
|
void InitializeStub() {
|
||||||
stub_ = cartographer::common::make_unique<mapping::MapBuilderStub>(
|
stub_ = common::make_unique<MapBuilderStub>(
|
||||||
map_builder_server_options_.server_address());
|
map_builder_server_options_.server_address());
|
||||||
EXPECT_TRUE(stub_ != nullptr);
|
EXPECT_TRUE(stub_ != nullptr);
|
||||||
}
|
}
|
||||||
|
@ -120,15 +116,15 @@ class ClientServerTest : public ::testing::Test {
|
||||||
proto::MapBuilderServerOptions map_builder_server_options_;
|
proto::MapBuilderServerOptions map_builder_server_options_;
|
||||||
testing::MockMapBuilder* mock_map_builder_;
|
testing::MockMapBuilder* mock_map_builder_;
|
||||||
std::unique_ptr<testing::MockTrajectoryBuilder> mock_trajectory_builder_;
|
std::unique_ptr<testing::MockTrajectoryBuilder> mock_trajectory_builder_;
|
||||||
cartographer::mapping::proto::TrajectoryBuilderOptions
|
::cartographer::mapping::proto::TrajectoryBuilderOptions
|
||||||
trajectory_builder_options_;
|
trajectory_builder_options_;
|
||||||
std::unique_ptr<MapBuilderServer> server_;
|
std::unique_ptr<MapBuilderServer> server_;
|
||||||
std::unique_ptr<mapping::MapBuilderStub> stub_;
|
std::unique_ptr<MapBuilderStub> stub_;
|
||||||
TrajectoryBuilderInterface::LocalSlamResultCallback
|
TrajectoryBuilderInterface::LocalSlamResultCallback
|
||||||
local_slam_result_callback_;
|
local_slam_result_callback_;
|
||||||
std::condition_variable local_slam_result_condition_;
|
std::condition_variable local_slam_result_condition_;
|
||||||
std::mutex local_slam_result_mutex_;
|
std::mutex local_slam_result_mutex_;
|
||||||
std::vector<cartographer::transform::Rigid3d> local_slam_result_poses_;
|
std::vector<transform::Rigid3d> local_slam_result_poses_;
|
||||||
};
|
};
|
||||||
|
|
||||||
TEST_F(ClientServerTest, StartAndStopServer) {
|
TEST_F(ClientServerTest, StartAndStopServer) {
|
||||||
|
@ -176,9 +172,9 @@ TEST_F(ClientServerTest, AddSensorData) {
|
||||||
{kImuSensorId}, trajectory_builder_options_, nullptr);
|
{kImuSensorId}, trajectory_builder_options_, nullptr);
|
||||||
TrajectoryBuilderInterface* trajectory_stub =
|
TrajectoryBuilderInterface* trajectory_stub =
|
||||||
stub_->GetTrajectoryBuilder(trajectory_id);
|
stub_->GetTrajectoryBuilder(trajectory_id);
|
||||||
cartographer::sensor::ImuData imu_data{
|
sensor::ImuData imu_data{common::FromUniversal(42),
|
||||||
cartographer::common::FromUniversal(42), Eigen::Vector3d(0., 0., 9.8),
|
Eigen::Vector3d(0., 0., 9.8),
|
||||||
Eigen::Vector3d::Zero()};
|
Eigen::Vector3d::Zero()};
|
||||||
trajectory_stub->AddSensorData(kImuSensorId.id, imu_data);
|
trajectory_stub->AddSensorData(kImuSensorId.id, imu_data);
|
||||||
stub_->FinishTrajectory(trajectory_id);
|
stub_->FinishTrajectory(trajectory_id);
|
||||||
server_->Shutdown();
|
server_->Shutdown();
|
||||||
|
@ -198,15 +194,14 @@ TEST_F(ClientServerTest, AddSensorDataWithMock) {
|
||||||
EXPECT_EQ(trajectory_id, 3);
|
EXPECT_EQ(trajectory_id, 3);
|
||||||
EXPECT_CALL(*mock_map_builder_, GetTrajectoryBuilder(_))
|
EXPECT_CALL(*mock_map_builder_, GetTrajectoryBuilder(_))
|
||||||
.WillRepeatedly(::testing::Return(mock_trajectory_builder_.get()));
|
.WillRepeatedly(::testing::Return(mock_trajectory_builder_.get()));
|
||||||
cartographer::mapping::TrajectoryBuilderInterface* trajectory_stub =
|
mapping::TrajectoryBuilderInterface* trajectory_stub =
|
||||||
stub_->GetTrajectoryBuilder(trajectory_id);
|
stub_->GetTrajectoryBuilder(trajectory_id);
|
||||||
cartographer::sensor::ImuData imu_data{
|
sensor::ImuData imu_data{common::FromUniversal(42),
|
||||||
cartographer::common::FromUniversal(42), Eigen::Vector3d(0., 0., 9.8),
|
Eigen::Vector3d(0., 0., 9.8),
|
||||||
Eigen::Vector3d::Zero()};
|
Eigen::Vector3d::Zero()};
|
||||||
EXPECT_CALL(*mock_trajectory_builder_,
|
EXPECT_CALL(*mock_trajectory_builder_,
|
||||||
AddSensorData(
|
AddSensorData(::testing::StrEq(kImuSensorId.id),
|
||||||
::testing::StrEq(kImuSensorId.id),
|
::testing::Matcher<const sensor::ImuData&>(_)))
|
||||||
::testing::Matcher<const cartographer::sensor::ImuData&>(_)))
|
|
||||||
.WillOnce(::testing::Return());
|
.WillOnce(::testing::Return());
|
||||||
trajectory_stub->AddSensorData(kImuSensorId.id, imu_data);
|
trajectory_stub->AddSensorData(kImuSensorId.id, imu_data);
|
||||||
EXPECT_CALL(*mock_map_builder_, FinishTrajectory(trajectory_id));
|
EXPECT_CALL(*mock_map_builder_, FinishTrajectory(trajectory_id));
|
||||||
|
@ -223,9 +218,8 @@ TEST_F(ClientServerTest, LocalSlam2D) {
|
||||||
local_slam_result_callback_);
|
local_slam_result_callback_);
|
||||||
TrajectoryBuilderInterface* trajectory_stub =
|
TrajectoryBuilderInterface* trajectory_stub =
|
||||||
stub_->GetTrajectoryBuilder(trajectory_id);
|
stub_->GetTrajectoryBuilder(trajectory_id);
|
||||||
const auto measurements =
|
const auto measurements = mapping::test::GenerateFakeRangeMeasurements(
|
||||||
cartographer::mapping::test::GenerateFakeRangeMeasurements(
|
kTravelDistance, kDuration, kTimeStep);
|
||||||
kTravelDistance, kDuration, kTimeStep);
|
|
||||||
for (const auto& measurement : measurements) {
|
for (const auto& measurement : measurements) {
|
||||||
trajectory_stub->AddSensorData(kRangeSensorId.id, measurement);
|
trajectory_stub->AddSensorData(kRangeSensorId.id, measurement);
|
||||||
}
|
}
|
||||||
|
@ -262,12 +256,11 @@ TEST_F(ClientServerTest, GlobalSlam3D) {
|
||||||
local_slam_result_callback_);
|
local_slam_result_callback_);
|
||||||
TrajectoryBuilderInterface* trajectory_stub =
|
TrajectoryBuilderInterface* trajectory_stub =
|
||||||
stub_->GetTrajectoryBuilder(trajectory_id);
|
stub_->GetTrajectoryBuilder(trajectory_id);
|
||||||
const auto measurements =
|
const auto measurements = mapping::test::GenerateFakeRangeMeasurements(
|
||||||
cartographer::mapping::test::GenerateFakeRangeMeasurements(
|
kTravelDistance, kDuration, kTimeStep);
|
||||||
kTravelDistance, kDuration, kTimeStep);
|
|
||||||
for (const auto& measurement : measurements) {
|
for (const auto& measurement : measurements) {
|
||||||
cartographer::sensor::ImuData imu_data{
|
sensor::ImuData imu_data{
|
||||||
measurement.time - cartographer::common::FromSeconds(kTimeStep / 2),
|
measurement.time - common::FromSeconds(kTimeStep / 2),
|
||||||
Eigen::Vector3d(0., 0., 9.8), Eigen::Vector3d::Zero()};
|
Eigen::Vector3d(0., 0., 9.8), Eigen::Vector3d::Zero()};
|
||||||
trajectory_stub->AddSensorData(kImuSensorId.id, imu_data);
|
trajectory_stub->AddSensorData(kImuSensorId.id, imu_data);
|
||||||
trajectory_stub->AddSensorData(kRangeSensorId.id, measurement);
|
trajectory_stub->AddSensorData(kRangeSensorId.id, measurement);
|
||||||
|
@ -285,4 +278,5 @@ TEST_F(ClientServerTest, GlobalSlam3D) {
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -25,16 +25,16 @@
|
||||||
#include "grpc++/impl/codegen/client_unary_call.h"
|
#include "grpc++/impl/codegen/client_unary_call.h"
|
||||||
#include "grpc++/impl/codegen/sync_stream.h"
|
#include "grpc++/impl/codegen/sync_stream.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
template <typename RpcHandlerType>
|
template <typename RpcHandlerType>
|
||||||
class Client {
|
class Client {
|
||||||
public:
|
public:
|
||||||
Client(std::shared_ptr<grpc::Channel> channel, RetryStrategy retry_strategy)
|
Client(std::shared_ptr<::grpc::Channel> channel, RetryStrategy retry_strategy)
|
||||||
: channel_(channel),
|
: channel_(channel),
|
||||||
client_context_(
|
client_context_(common::make_unique<::grpc::ClientContext>()),
|
||||||
cartographer::common::make_unique<grpc::ClientContext>()),
|
|
||||||
rpc_method_name_(
|
rpc_method_name_(
|
||||||
RpcHandlerInterface::Instantiate<RpcHandlerType>()->method_name()),
|
RpcHandlerInterface::Instantiate<RpcHandlerType>()->method_name()),
|
||||||
rpc_method_(rpc_method_name_.c_str(),
|
rpc_method_(rpc_method_name_.c_str(),
|
||||||
|
@ -47,10 +47,9 @@ class Client {
|
||||||
<< "Retry is currently only support for NORMAL_RPC.";
|
<< "Retry is currently only support for NORMAL_RPC.";
|
||||||
}
|
}
|
||||||
|
|
||||||
Client(std::shared_ptr<grpc::Channel> channel)
|
Client(std::shared_ptr<::grpc::Channel> channel)
|
||||||
: channel_(channel),
|
: channel_(channel),
|
||||||
client_context_(
|
client_context_(common::make_unique<::grpc::ClientContext>()),
|
||||||
cartographer::common::make_unique<grpc::ClientContext>()),
|
|
||||||
rpc_method_name_(
|
rpc_method_name_(
|
||||||
RpcHandlerInterface::Instantiate<RpcHandlerType>()->method_name()),
|
RpcHandlerInterface::Instantiate<RpcHandlerType>()->method_name()),
|
||||||
rpc_method_(rpc_method_name_.c_str(),
|
rpc_method_(rpc_method_name_.c_str(),
|
||||||
|
@ -60,10 +59,10 @@ class Client {
|
||||||
|
|
||||||
bool Read(typename RpcHandlerType::ResponseType *response) {
|
bool Read(typename RpcHandlerType::ResponseType *response) {
|
||||||
switch (rpc_method_.method_type()) {
|
switch (rpc_method_.method_type()) {
|
||||||
case grpc::internal::RpcMethod::BIDI_STREAMING:
|
case ::grpc::internal::RpcMethod::BIDI_STREAMING:
|
||||||
InstantiateClientReaderWriterIfNeeded();
|
InstantiateClientReaderWriterIfNeeded();
|
||||||
return client_reader_writer_->Read(response);
|
return client_reader_writer_->Read(response);
|
||||||
case grpc::internal::RpcMethod::SERVER_STREAMING:
|
case ::grpc::internal::RpcMethod::SERVER_STREAMING:
|
||||||
CHECK(client_reader_);
|
CHECK(client_reader_);
|
||||||
return client_reader_->Read(response);
|
return client_reader_->Read(response);
|
||||||
default:
|
default:
|
||||||
|
@ -80,10 +79,10 @@ class Client {
|
||||||
|
|
||||||
bool WritesDone() {
|
bool WritesDone() {
|
||||||
switch (rpc_method_.method_type()) {
|
switch (rpc_method_.method_type()) {
|
||||||
case grpc::internal::RpcMethod::CLIENT_STREAMING:
|
case ::grpc::internal::RpcMethod::CLIENT_STREAMING:
|
||||||
InstantiateClientWriterIfNeeded();
|
InstantiateClientWriterIfNeeded();
|
||||||
return client_writer_->WritesDone();
|
return client_writer_->WritesDone();
|
||||||
case grpc::internal::RpcMethod::BIDI_STREAMING:
|
case ::grpc::internal::RpcMethod::BIDI_STREAMING:
|
||||||
InstantiateClientReaderWriterIfNeeded();
|
InstantiateClientReaderWriterIfNeeded();
|
||||||
return client_reader_writer_->WritesDone();
|
return client_reader_writer_->WritesDone();
|
||||||
default:
|
default:
|
||||||
|
@ -91,15 +90,15 @@ class Client {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
grpc::Status Finish() {
|
::grpc::Status Finish() {
|
||||||
switch (rpc_method_.method_type()) {
|
switch (rpc_method_.method_type()) {
|
||||||
case grpc::internal::RpcMethod::CLIENT_STREAMING:
|
case ::grpc::internal::RpcMethod::CLIENT_STREAMING:
|
||||||
InstantiateClientWriterIfNeeded();
|
InstantiateClientWriterIfNeeded();
|
||||||
return client_writer_->Finish();
|
return client_writer_->Finish();
|
||||||
case grpc::internal::RpcMethod::BIDI_STREAMING:
|
case ::grpc::internal::RpcMethod::BIDI_STREAMING:
|
||||||
InstantiateClientReaderWriterIfNeeded();
|
InstantiateClientReaderWriterIfNeeded();
|
||||||
return client_reader_writer_->Finish();
|
return client_reader_writer_->Finish();
|
||||||
case grpc::internal::RpcMethod::SERVER_STREAMING:
|
case ::grpc::internal::RpcMethod::SERVER_STREAMING:
|
||||||
CHECK(client_reader_);
|
CHECK(client_reader_);
|
||||||
return client_reader_->Finish();
|
return client_reader_->Finish();
|
||||||
default:
|
default:
|
||||||
|
@ -108,28 +107,29 @@ class Client {
|
||||||
}
|
}
|
||||||
|
|
||||||
const typename RpcHandlerType::ResponseType &response() {
|
const typename RpcHandlerType::ResponseType &response() {
|
||||||
CHECK(rpc_method_.method_type() == grpc::internal::RpcMethod::NORMAL_RPC ||
|
CHECK(rpc_method_.method_type() ==
|
||||||
|
::grpc::internal::RpcMethod::NORMAL_RPC ||
|
||||||
rpc_method_.method_type() ==
|
rpc_method_.method_type() ==
|
||||||
grpc::internal::RpcMethod::CLIENT_STREAMING);
|
::grpc::internal::RpcMethod::CLIENT_STREAMING);
|
||||||
return response_;
|
return response_;
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void Reset() {
|
void Reset() {
|
||||||
client_context_ = cartographer::common::make_unique<grpc::ClientContext>();
|
client_context_ = common::make_unique<::grpc::ClientContext>();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool WriteImpl(const typename RpcHandlerType::RequestType &request) {
|
bool WriteImpl(const typename RpcHandlerType::RequestType &request) {
|
||||||
switch (rpc_method_.method_type()) {
|
switch (rpc_method_.method_type()) {
|
||||||
case grpc::internal::RpcMethod::NORMAL_RPC:
|
case ::grpc::internal::RpcMethod::NORMAL_RPC:
|
||||||
return MakeBlockingUnaryCall(request, &response_).ok();
|
return MakeBlockingUnaryCall(request, &response_).ok();
|
||||||
case grpc::internal::RpcMethod::CLIENT_STREAMING:
|
case ::grpc::internal::RpcMethod::CLIENT_STREAMING:
|
||||||
InstantiateClientWriterIfNeeded();
|
InstantiateClientWriterIfNeeded();
|
||||||
return client_writer_->Write(request);
|
return client_writer_->Write(request);
|
||||||
case grpc::internal::RpcMethod::BIDI_STREAMING:
|
case ::grpc::internal::RpcMethod::BIDI_STREAMING:
|
||||||
InstantiateClientReaderWriterIfNeeded();
|
InstantiateClientReaderWriterIfNeeded();
|
||||||
return client_reader_writer_->Write(request);
|
return client_reader_writer_->Write(request);
|
||||||
case grpc::internal::RpcMethod::SERVER_STREAMING:
|
case ::grpc::internal::RpcMethod::SERVER_STREAMING:
|
||||||
InstantiateClientReader(request);
|
InstantiateClientReader(request);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -138,10 +138,10 @@ class Client {
|
||||||
|
|
||||||
void InstantiateClientWriterIfNeeded() {
|
void InstantiateClientWriterIfNeeded() {
|
||||||
CHECK_EQ(rpc_method_.method_type(),
|
CHECK_EQ(rpc_method_.method_type(),
|
||||||
grpc::internal::RpcMethod::CLIENT_STREAMING);
|
::grpc::internal::RpcMethod::CLIENT_STREAMING);
|
||||||
if (!client_writer_) {
|
if (!client_writer_) {
|
||||||
client_writer_.reset(
|
client_writer_.reset(
|
||||||
grpc::internal::
|
::grpc::internal::
|
||||||
ClientWriterFactory<typename RpcHandlerType::RequestType>::Create(
|
ClientWriterFactory<typename RpcHandlerType::RequestType>::Create(
|
||||||
channel_.get(), rpc_method_, client_context_.get(),
|
channel_.get(), rpc_method_, client_context_.get(),
|
||||||
&response_));
|
&response_));
|
||||||
|
@ -150,10 +150,10 @@ class Client {
|
||||||
|
|
||||||
void InstantiateClientReaderWriterIfNeeded() {
|
void InstantiateClientReaderWriterIfNeeded() {
|
||||||
CHECK_EQ(rpc_method_.method_type(),
|
CHECK_EQ(rpc_method_.method_type(),
|
||||||
grpc::internal::RpcMethod::BIDI_STREAMING);
|
::grpc::internal::RpcMethod::BIDI_STREAMING);
|
||||||
if (!client_reader_writer_) {
|
if (!client_reader_writer_) {
|
||||||
client_reader_writer_.reset(
|
client_reader_writer_.reset(
|
||||||
grpc::internal::ClientReaderWriterFactory<
|
::grpc::internal::ClientReaderWriterFactory<
|
||||||
typename RpcHandlerType::RequestType,
|
typename RpcHandlerType::RequestType,
|
||||||
typename RpcHandlerType::ResponseType>::Create(channel_.get(),
|
typename RpcHandlerType::ResponseType>::Create(channel_.get(),
|
||||||
rpc_method_,
|
rpc_method_,
|
||||||
|
@ -165,39 +165,41 @@ class Client {
|
||||||
void InstantiateClientReader(
|
void InstantiateClientReader(
|
||||||
const typename RpcHandlerType::RequestType &request) {
|
const typename RpcHandlerType::RequestType &request) {
|
||||||
CHECK_EQ(rpc_method_.method_type(),
|
CHECK_EQ(rpc_method_.method_type(),
|
||||||
grpc::internal::RpcMethod::SERVER_STREAMING);
|
::grpc::internal::RpcMethod::SERVER_STREAMING);
|
||||||
client_reader_.reset(
|
client_reader_.reset(
|
||||||
grpc::internal::
|
::grpc::internal::
|
||||||
ClientReaderFactory<typename RpcHandlerType::ResponseType>::Create(
|
ClientReaderFactory<typename RpcHandlerType::ResponseType>::Create(
|
||||||
channel_.get(), rpc_method_, client_context_.get(), request));
|
channel_.get(), rpc_method_, client_context_.get(), request));
|
||||||
}
|
}
|
||||||
|
|
||||||
grpc::Status MakeBlockingUnaryCall(
|
::grpc::Status MakeBlockingUnaryCall(
|
||||||
const typename RpcHandlerType::RequestType &request,
|
const typename RpcHandlerType::RequestType &request,
|
||||||
typename RpcHandlerType::ResponseType *response) {
|
typename RpcHandlerType::ResponseType *response) {
|
||||||
CHECK_EQ(rpc_method_.method_type(), grpc::internal::RpcMethod::NORMAL_RPC);
|
CHECK_EQ(rpc_method_.method_type(),
|
||||||
|
::grpc::internal::RpcMethod::NORMAL_RPC);
|
||||||
return ::grpc::internal::BlockingUnaryCall(
|
return ::grpc::internal::BlockingUnaryCall(
|
||||||
channel_.get(), rpc_method_, client_context_.get(), request, response);
|
channel_.get(), rpc_method_, client_context_.get(), request, response);
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_ptr<grpc::Channel> channel_;
|
std::shared_ptr<::grpc::Channel> channel_;
|
||||||
std::unique_ptr<grpc::ClientContext> client_context_;
|
std::unique_ptr<::grpc::ClientContext> client_context_;
|
||||||
const std::string rpc_method_name_;
|
const std::string rpc_method_name_;
|
||||||
const ::grpc::internal::RpcMethod rpc_method_;
|
const ::grpc::internal::RpcMethod rpc_method_;
|
||||||
|
|
||||||
std::unique_ptr<grpc::ClientWriter<typename RpcHandlerType::RequestType>>
|
std::unique_ptr<::grpc::ClientWriter<typename RpcHandlerType::RequestType>>
|
||||||
client_writer_;
|
client_writer_;
|
||||||
std::unique_ptr<
|
std::unique_ptr<
|
||||||
grpc::ClientReaderWriter<typename RpcHandlerType::RequestType,
|
::grpc::ClientReaderWriter<typename RpcHandlerType::RequestType,
|
||||||
typename RpcHandlerType::ResponseType>>
|
typename RpcHandlerType::ResponseType>>
|
||||||
client_reader_writer_;
|
client_reader_writer_;
|
||||||
std::unique_ptr<grpc::ClientReader<typename RpcHandlerType::ResponseType>>
|
std::unique_ptr<::grpc::ClientReader<typename RpcHandlerType::ResponseType>>
|
||||||
client_reader_;
|
client_reader_;
|
||||||
typename RpcHandlerType::ResponseType response_;
|
typename RpcHandlerType::ResponseType response_;
|
||||||
RetryStrategy retry_strategy_;
|
RetryStrategy retry_strategy_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_CLIENT_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_CLIENT_H
|
||||||
|
|
|
@ -19,7 +19,8 @@
|
||||||
#include "cartographer/common/make_unique.h"
|
#include "cartographer/common/make_unique.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
CompletionQueueThread::CompletionQueueThread(
|
CompletionQueueThread::CompletionQueueThread(
|
||||||
|
@ -32,7 +33,7 @@ CompletionQueueThread::CompletionQueueThread(
|
||||||
|
|
||||||
void CompletionQueueThread::Start(CompletionQueueRunner runner) {
|
void CompletionQueueThread::Start(CompletionQueueRunner runner) {
|
||||||
CHECK(!worker_thread_);
|
CHECK(!worker_thread_);
|
||||||
worker_thread_ = cartographer::common::make_unique<std::thread>(
|
worker_thread_ = common::make_unique<std::thread>(
|
||||||
[this, runner]() { runner(this->completion_queue_.get()); });
|
[this, runner]() { runner(this->completion_queue_.get()); });
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -43,4 +44,5 @@ void CompletionQueueThread::Shutdown() {
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include <memory>
|
#include <memory>
|
||||||
#include <thread>
|
#include <thread>
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
class CompletionQueueThread {
|
class CompletionQueueThread {
|
||||||
|
@ -43,6 +44,7 @@ class CompletionQueueThread {
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_COMPLETION_QUEUE_THREAD_H
|
#endif // CARTOGRAPHER_COMPLETION_QUEUE_THREAD_H
|
||||||
|
|
|
@ -19,11 +19,12 @@
|
||||||
#include "cartographer/common/make_unique.h"
|
#include "cartographer/common/make_unique.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
EventQueueThread::EventQueueThread() {
|
EventQueueThread::EventQueueThread() {
|
||||||
event_queue_ = cartographer::common::make_unique<EventQueue>();
|
event_queue_ = common::make_unique<EventQueue>();
|
||||||
}
|
}
|
||||||
|
|
||||||
EventQueue* EventQueueThread::event_queue() { return event_queue_.get(); }
|
EventQueue* EventQueueThread::event_queue() { return event_queue_.get(); }
|
||||||
|
@ -31,7 +32,7 @@ EventQueue* EventQueueThread::event_queue() { return event_queue_.get(); }
|
||||||
void EventQueueThread::Start(EventQueueRunner runner) {
|
void EventQueueThread::Start(EventQueueRunner runner) {
|
||||||
CHECK(!thread_);
|
CHECK(!thread_);
|
||||||
EventQueue* event_queue = event_queue_.get();
|
EventQueue* event_queue = event_queue_.get();
|
||||||
thread_ = cartographer::common::make_unique<std::thread>(
|
thread_ = common::make_unique<std::thread>(
|
||||||
[event_queue, runner]() { runner(event_queue); });
|
[event_queue, runner]() { runner(event_queue); });
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -41,4 +42,5 @@ void EventQueueThread::Shutdown() {
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
#include "cartographer/common/blocking_queue.h"
|
#include "cartographer/common/blocking_queue.h"
|
||||||
#include "cartographer_grpc/internal/framework/rpc.h"
|
#include "cartographer_grpc/internal/framework/rpc.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
class EventQueueThread {
|
class EventQueueThread {
|
||||||
|
@ -43,6 +44,7 @@ class EventQueueThread {
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_EVENT_QUEUE_THREAD_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_EVENT_QUEUE_THREAD_H
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "cartographer/common/mutex.h"
|
#include "cartographer/common/mutex.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
// Implementations of this class allow RPC handlers to share state among one
|
// Implementations of this class allow RPC handlers to share state among one
|
||||||
|
@ -39,27 +40,27 @@ class ExecutionContext {
|
||||||
ContextType* operator->() {
|
ContextType* operator->() {
|
||||||
return static_cast<ContextType*>(execution_context_);
|
return static_cast<ContextType*>(execution_context_);
|
||||||
}
|
}
|
||||||
Synchronized(cartographer::common::Mutex* lock,
|
Synchronized(common::Mutex* lock, ExecutionContext* execution_context)
|
||||||
ExecutionContext* execution_context)
|
|
||||||
: locker_(lock), execution_context_(execution_context) {}
|
: locker_(lock), execution_context_(execution_context) {}
|
||||||
Synchronized(const Synchronized&) = delete;
|
Synchronized(const Synchronized&) = delete;
|
||||||
Synchronized(Synchronized&&) = delete;
|
Synchronized(Synchronized&&) = delete;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
cartographer::common::MutexLocker locker_;
|
common::MutexLocker locker_;
|
||||||
ExecutionContext* execution_context_;
|
ExecutionContext* execution_context_;
|
||||||
};
|
};
|
||||||
ExecutionContext() = default;
|
ExecutionContext() = default;
|
||||||
virtual ~ExecutionContext() = default;
|
virtual ~ExecutionContext() = default;
|
||||||
ExecutionContext(const ExecutionContext&) = delete;
|
ExecutionContext(const ExecutionContext&) = delete;
|
||||||
ExecutionContext& operator=(const ExecutionContext&) = delete;
|
ExecutionContext& operator=(const ExecutionContext&) = delete;
|
||||||
cartographer::common::Mutex* lock() { return &lock_; }
|
common::Mutex* lock() { return &lock_; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
cartographer::common::Mutex lock_;
|
common::Mutex lock_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_EXECUTION_CONTEXT_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_EXECUTION_CONTEXT_H
|
||||||
|
|
|
@ -14,7 +14,7 @@
|
||||||
|
|
||||||
syntax = "proto3";
|
syntax = "proto3";
|
||||||
|
|
||||||
package cartographer_grpc.framework.proto;
|
package cartographer.cloud.framework.proto;
|
||||||
|
|
||||||
message GetSumRequest {
|
message GetSumRequest {
|
||||||
int32 input = 1;
|
int32 input = 1;
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "cartographer_grpc/internal/framework/retry.h"
|
#include "cartographer_grpc/internal/framework/retry.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
RetryStrategy CreateRetryStrategy(RetryIndicator retry_indicator,
|
RetryStrategy CreateRetryStrategy(RetryIndicator retry_indicator,
|
||||||
|
@ -43,8 +44,8 @@ RetryDelayCalculator CreateBackoffDelayCalculator(Duration min_delay,
|
||||||
float backoff_factor) {
|
float backoff_factor) {
|
||||||
return [min_delay, backoff_factor](int failed_attempts) -> Duration {
|
return [min_delay, backoff_factor](int failed_attempts) -> Duration {
|
||||||
CHECK_GE(failed_attempts, 0);
|
CHECK_GE(failed_attempts, 0);
|
||||||
using cartographer::common::FromSeconds;
|
using common::FromSeconds;
|
||||||
using cartographer::common::ToSeconds;
|
using common::ToSeconds;
|
||||||
return FromSeconds(std::pow(backoff_factor, failed_attempts - 1) *
|
return FromSeconds(std::pow(backoff_factor, failed_attempts - 1) *
|
||||||
ToSeconds(min_delay));
|
ToSeconds(min_delay));
|
||||||
};
|
};
|
||||||
|
@ -87,4 +88,5 @@ bool RetryWithStrategy(RetryStrategy retry_strategy, std::function<bool()> op,
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,11 +21,12 @@
|
||||||
#include "cartographer/common/time.h"
|
#include "cartographer/common/time.h"
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
using cartographer::common::Duration;
|
using common::Duration;
|
||||||
using cartographer::common::optional;
|
using common::optional;
|
||||||
|
|
||||||
using RetryStrategy =
|
using RetryStrategy =
|
||||||
std::function<optional<Duration>(int /* failed_attempts */)>;
|
std::function<optional<Duration>(int /* failed_attempts */)>;
|
||||||
|
@ -46,6 +47,7 @@ bool RetryWithStrategy(RetryStrategy retry_strategy, std::function<bool()> op,
|
||||||
std::function<void()> reset = nullptr);
|
std::function<void()> reset = nullptr);
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_RETRY_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_RETRY_H
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "cartographer/common/make_unique.h"
|
#include "cartographer/common/make_unique.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -83,7 +84,7 @@ Rpc::Rpc(int method_index,
|
||||||
}
|
}
|
||||||
|
|
||||||
std::unique_ptr<Rpc> Rpc::Clone() {
|
std::unique_ptr<Rpc> Rpc::Clone() {
|
||||||
return cartographer::common::make_unique<Rpc>(
|
return common::make_unique<Rpc>(
|
||||||
method_index_, server_completion_queue_, event_queue_, execution_context_,
|
method_index_, server_completion_queue_, event_queue_, execution_context_,
|
||||||
rpc_handler_info_, service_, weak_ptr_factory_);
|
rpc_handler_info_, service_, weak_ptr_factory_);
|
||||||
}
|
}
|
||||||
|
@ -166,7 +167,7 @@ void Rpc::Finish(::grpc::Status status) {
|
||||||
void Rpc::HandleSendQueue() {
|
void Rpc::HandleSendQueue() {
|
||||||
SendItem send_item;
|
SendItem send_item;
|
||||||
{
|
{
|
||||||
cartographer::common::MutexLocker locker(&send_queue_lock_);
|
common::MutexLocker locker(&send_queue_lock_);
|
||||||
if (send_queue_.empty() || IsRpcEventPending(Event::WRITE) ||
|
if (send_queue_.empty() || IsRpcEventPending(Event::WRITE) ||
|
||||||
IsRpcEventPending(Event::FINISH)) {
|
IsRpcEventPending(Event::FINISH)) {
|
||||||
return;
|
return;
|
||||||
|
@ -255,7 +256,7 @@ bool* Rpc::GetRpcEventState(Event event) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rpc::EnqueueMessage(SendItem&& send_item) {
|
void Rpc::EnqueueMessage(SendItem&& send_item) {
|
||||||
cartographer::common::MutexLocker locker(&send_queue_lock_);
|
common::MutexLocker locker(&send_queue_lock_);
|
||||||
send_queue_.emplace(std::move(send_item));
|
send_queue_.emplace(std::move(send_item));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -319,23 +320,22 @@ void Rpc::InitializeReadersAndWriters(
|
||||||
switch (rpc_type) {
|
switch (rpc_type) {
|
||||||
case ::grpc::internal::RpcMethod::BIDI_STREAMING:
|
case ::grpc::internal::RpcMethod::BIDI_STREAMING:
|
||||||
server_async_reader_writer_ =
|
server_async_reader_writer_ =
|
||||||
cartographer::common::make_unique<::grpc::ServerAsyncReaderWriter<
|
common::make_unique<::grpc::ServerAsyncReaderWriter<
|
||||||
google::protobuf::Message, google::protobuf::Message>>(
|
google::protobuf::Message, google::protobuf::Message>>(
|
||||||
&server_context_);
|
&server_context_);
|
||||||
break;
|
break;
|
||||||
case ::grpc::internal::RpcMethod::CLIENT_STREAMING:
|
case ::grpc::internal::RpcMethod::CLIENT_STREAMING:
|
||||||
server_async_reader_ =
|
server_async_reader_ = common::make_unique<::grpc::ServerAsyncReader<
|
||||||
cartographer::common::make_unique<::grpc::ServerAsyncReader<
|
google::protobuf::Message, google::protobuf::Message>>(
|
||||||
google::protobuf::Message, google::protobuf::Message>>(
|
&server_context_);
|
||||||
&server_context_);
|
|
||||||
break;
|
break;
|
||||||
case ::grpc::internal::RpcMethod::NORMAL_RPC:
|
case ::grpc::internal::RpcMethod::NORMAL_RPC:
|
||||||
server_async_response_writer_ = cartographer::common::make_unique<
|
server_async_response_writer_ = common::make_unique<
|
||||||
::grpc::ServerAsyncResponseWriter<google::protobuf::Message>>(
|
::grpc::ServerAsyncResponseWriter<google::protobuf::Message>>(
|
||||||
&server_context_);
|
&server_context_);
|
||||||
break;
|
break;
|
||||||
case ::grpc::internal::RpcMethod::SERVER_STREAMING:
|
case ::grpc::internal::RpcMethod::SERVER_STREAMING:
|
||||||
server_async_writer_ = cartographer::common::make_unique<
|
server_async_writer_ = common::make_unique<
|
||||||
::grpc::ServerAsyncWriter<google::protobuf::Message>>(
|
::grpc::ServerAsyncWriter<google::protobuf::Message>>(
|
||||||
&server_context_);
|
&server_context_);
|
||||||
break;
|
break;
|
||||||
|
@ -343,14 +343,14 @@ void Rpc::InitializeReadersAndWriters(
|
||||||
}
|
}
|
||||||
|
|
||||||
ActiveRpcs::~ActiveRpcs() {
|
ActiveRpcs::~ActiveRpcs() {
|
||||||
cartographer::common::MutexLocker locker(&lock_);
|
common::MutexLocker locker(&lock_);
|
||||||
if (!rpcs_.empty()) {
|
if (!rpcs_.empty()) {
|
||||||
LOG(FATAL) << "RPCs still in flight!";
|
LOG(FATAL) << "RPCs still in flight!";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_ptr<Rpc> ActiveRpcs::Add(std::unique_ptr<Rpc> rpc) {
|
std::shared_ptr<Rpc> ActiveRpcs::Add(std::unique_ptr<Rpc> rpc) {
|
||||||
cartographer::common::MutexLocker locker(&lock_);
|
common::MutexLocker locker(&lock_);
|
||||||
std::shared_ptr<Rpc> shared_ptr_rpc = std::move(rpc);
|
std::shared_ptr<Rpc> shared_ptr_rpc = std::move(rpc);
|
||||||
const auto result = rpcs_.emplace(shared_ptr_rpc.get(), shared_ptr_rpc);
|
const auto result = rpcs_.emplace(shared_ptr_rpc.get(), shared_ptr_rpc);
|
||||||
CHECK(result.second) << "RPC already active.";
|
CHECK(result.second) << "RPC already active.";
|
||||||
|
@ -358,7 +358,7 @@ std::shared_ptr<Rpc> ActiveRpcs::Add(std::unique_ptr<Rpc> rpc) {
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ActiveRpcs::Remove(Rpc* rpc) {
|
bool ActiveRpcs::Remove(Rpc* rpc) {
|
||||||
cartographer::common::MutexLocker locker(&lock_);
|
common::MutexLocker locker(&lock_);
|
||||||
auto it = rpcs_.find(rpc);
|
auto it = rpcs_.find(rpc);
|
||||||
if (it != rpcs_.end()) {
|
if (it != rpcs_.end()) {
|
||||||
rpcs_.erase(it);
|
rpcs_.erase(it);
|
||||||
|
@ -372,11 +372,12 @@ Rpc::WeakPtrFactory ActiveRpcs::GetWeakPtrFactory() {
|
||||||
}
|
}
|
||||||
|
|
||||||
std::weak_ptr<Rpc> ActiveRpcs::GetWeakPtr(Rpc* rpc) {
|
std::weak_ptr<Rpc> ActiveRpcs::GetWeakPtr(Rpc* rpc) {
|
||||||
cartographer::common::MutexLocker locker(&lock_);
|
common::MutexLocker locker(&lock_);
|
||||||
auto it = rpcs_.find(rpc);
|
auto it = rpcs_.find(rpc);
|
||||||
CHECK(it != rpcs_.end());
|
CHECK(it != rpcs_.end());
|
||||||
return it->second;
|
return it->second;
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -32,7 +32,8 @@
|
||||||
#include "grpc++/impl/codegen/proto_utils.h"
|
#include "grpc++/impl/codegen/proto_utils.h"
|
||||||
#include "grpc++/impl/codegen/service_type.h"
|
#include "grpc++/impl/codegen/service_type.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
class Service;
|
class Service;
|
||||||
|
@ -77,7 +78,7 @@ class Rpc {
|
||||||
};
|
};
|
||||||
|
|
||||||
using UniqueEventPtr = std::unique_ptr<EventBase, EventDeleter>;
|
using UniqueEventPtr = std::unique_ptr<EventBase, EventDeleter>;
|
||||||
using EventQueue = cartographer::common::BlockingQueue<UniqueEventPtr>;
|
using EventQueue = common::BlockingQueue<UniqueEventPtr>;
|
||||||
|
|
||||||
// Flows through gRPC's CompletionQueue and then our EventQueue.
|
// Flows through gRPC's CompletionQueue and then our EventQueue.
|
||||||
struct CompletionQueueRpcEvent : public EventBase {
|
struct CompletionQueueRpcEvent : public EventBase {
|
||||||
|
@ -180,7 +181,7 @@ class Rpc {
|
||||||
std::unique_ptr<::grpc::ServerAsyncWriter<google::protobuf::Message>>
|
std::unique_ptr<::grpc::ServerAsyncWriter<google::protobuf::Message>>
|
||||||
server_async_writer_;
|
server_async_writer_;
|
||||||
|
|
||||||
cartographer::common::Mutex send_queue_lock_;
|
common::Mutex send_queue_lock_;
|
||||||
std::queue<SendItem> send_queue_;
|
std::queue<SendItem> send_queue_;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -201,11 +202,12 @@ class ActiveRpcs {
|
||||||
private:
|
private:
|
||||||
std::weak_ptr<Rpc> GetWeakPtr(Rpc* rpc);
|
std::weak_ptr<Rpc> GetWeakPtr(Rpc* rpc);
|
||||||
|
|
||||||
cartographer::common::Mutex lock_;
|
common::Mutex lock_;
|
||||||
std::map<Rpc*, std::shared_ptr<Rpc>> rpcs_;
|
std::map<Rpc*, std::shared_ptr<Rpc>> rpcs_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_RPC_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_RPC_H
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#include "google/protobuf/message.h"
|
#include "google/protobuf/message.h"
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
template <typename Incoming, typename Outgoing>
|
template <typename Incoming, typename Outgoing>
|
||||||
|
@ -86,6 +87,7 @@ class RpcHandler : public RpcHandlerInterface {
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_RPC_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_RPC_HANDLER_H
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "google/protobuf/message.h"
|
#include "google/protobuf/message.h"
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
class Rpc;
|
class Rpc;
|
||||||
|
@ -43,7 +44,7 @@ class RpcHandlerInterface {
|
||||||
virtual void OnFinish(){};
|
virtual void OnFinish(){};
|
||||||
template <class RpcHandlerType>
|
template <class RpcHandlerType>
|
||||||
static std::unique_ptr<RpcHandlerType> Instantiate() {
|
static std::unique_ptr<RpcHandlerType> Instantiate() {
|
||||||
return cartographer::common::make_unique<RpcHandlerType>();
|
return common::make_unique<RpcHandlerType>();
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -54,11 +55,12 @@ struct RpcHandlerInfo {
|
||||||
const google::protobuf::Descriptor* request_descriptor;
|
const google::protobuf::Descriptor* request_descriptor;
|
||||||
const google::protobuf::Descriptor* response_descriptor;
|
const google::protobuf::Descriptor* response_descriptor;
|
||||||
const RpcHandlerFactory rpc_handler_factory;
|
const RpcHandlerFactory rpc_handler_factory;
|
||||||
const grpc::internal::RpcMethod::RpcType rpc_type;
|
const ::grpc::internal::RpcMethod::RpcType rpc_type;
|
||||||
const std::string fully_qualified_name;
|
const std::string fully_qualified_name;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_RPC_HANDLER_INTERFACE_H_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_RPC_HANDLER_INTERFACE_H_H
|
||||||
|
|
|
@ -18,12 +18,12 @@
|
||||||
|
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
const cartographer::common::Duration kPopEventTimeout =
|
const common::Duration kPopEventTimeout = common::FromMilliseconds(100);
|
||||||
cartographer::common::FromMilliseconds(100);
|
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
|
|
||||||
|
@ -61,7 +61,7 @@ std::unique_ptr<Server> Server::Builder::Build() {
|
||||||
|
|
||||||
Server::Server(const Options& options) : options_(options) {
|
Server::Server(const Options& options) : options_(options) {
|
||||||
server_builder_.AddListeningPort(options_.server_address,
|
server_builder_.AddListeningPort(options_.server_address,
|
||||||
grpc::InsecureServerCredentials());
|
::grpc::InsecureServerCredentials());
|
||||||
|
|
||||||
// Set up event queue threads.
|
// Set up event queue threads.
|
||||||
event_queue_threads_ =
|
event_queue_threads_ =
|
||||||
|
@ -99,7 +99,7 @@ void Server::RunCompletionQueue(
|
||||||
}
|
}
|
||||||
|
|
||||||
EventQueue* Server::SelectNextEventQueueRoundRobin() {
|
EventQueue* Server::SelectNextEventQueueRoundRobin() {
|
||||||
cartographer::common::MutexLocker locker(¤t_event_queue_id_lock_);
|
common::MutexLocker locker(¤t_event_queue_id_lock_);
|
||||||
current_event_queue_id_ =
|
current_event_queue_id_ =
|
||||||
(current_event_queue_id_ + 1) % options_.num_event_threads;
|
(current_event_queue_id_ + 1) % options_.num_event_threads;
|
||||||
return event_queue_threads_.at(current_event_queue_id_).event_queue();
|
return event_queue_threads_.at(current_event_queue_id_).event_queue();
|
||||||
|
@ -189,4 +189,5 @@ void Server::SetExecutionContext(
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -31,7 +31,8 @@
|
||||||
#include "cartographer_grpc/internal/framework/service.h"
|
#include "cartographer_grpc/internal/framework/service.h"
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
class Server {
|
class Server {
|
||||||
|
@ -71,7 +72,7 @@ class Server {
|
||||||
RpcHandlerType::ResponseType::default_instance().GetDescriptor(),
|
RpcHandlerType::ResponseType::default_instance().GetDescriptor(),
|
||||||
[](Rpc* const rpc, ExecutionContext* const execution_context) {
|
[](Rpc* const rpc, ExecutionContext* const execution_context) {
|
||||||
std::unique_ptr<RpcHandlerInterface> rpc_handler =
|
std::unique_ptr<RpcHandlerInterface> rpc_handler =
|
||||||
cartographer::common::make_unique<RpcHandlerType>();
|
common::make_unique<RpcHandlerType>();
|
||||||
rpc_handler->SetRpc(rpc);
|
rpc_handler->SetRpc(rpc);
|
||||||
rpc_handler->SetExecutionContext(execution_context);
|
rpc_handler->SetExecutionContext(execution_context);
|
||||||
return rpc_handler;
|
return rpc_handler;
|
||||||
|
@ -181,7 +182,7 @@ class Server {
|
||||||
|
|
||||||
// Threads processing RPC events.
|
// Threads processing RPC events.
|
||||||
std::vector<EventQueueThread> event_queue_threads_;
|
std::vector<EventQueueThread> event_queue_threads_;
|
||||||
cartographer::common::Mutex current_event_queue_id_lock_;
|
common::Mutex current_event_queue_id_lock_;
|
||||||
int current_event_queue_id_ = 0;
|
int current_event_queue_id_ = 0;
|
||||||
|
|
||||||
// Map of service names to services.
|
// Map of service names to services.
|
||||||
|
@ -193,6 +194,7 @@ class Server {
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_SERVER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_SERVER_H
|
||||||
|
|
|
@ -27,11 +27,13 @@
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
using EchoResponder = std::function<bool()>;
|
using EchoResponder = std::function<bool()>;
|
||||||
|
|
||||||
class MathServerContext : public ExecutionContext {
|
class MathServerContext : public ExecutionContext {
|
||||||
public:
|
public:
|
||||||
int additional_increment() { return 10; }
|
int additional_increment() { return 10; }
|
||||||
|
@ -42,7 +44,7 @@ class GetSumHandler
|
||||||
: public RpcHandler<Stream<proto::GetSumRequest>, proto::GetSumResponse> {
|
: public RpcHandler<Stream<proto::GetSumRequest>, proto::GetSumResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.framework.proto.Math/GetSum";
|
return "/cartographer.cloud.framework.proto.Math/GetSum";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::GetSumRequest& request) override {
|
void OnRequest(const proto::GetSumRequest& request) override {
|
||||||
sum_ += GetContext<MathServerContext>()->additional_increment();
|
sum_ += GetContext<MathServerContext>()->additional_increment();
|
||||||
|
@ -50,7 +52,7 @@ class GetSumHandler
|
||||||
}
|
}
|
||||||
|
|
||||||
void OnReadsDone() override {
|
void OnReadsDone() override {
|
||||||
auto response = cartographer::common::make_unique<proto::GetSumResponse>();
|
auto response = common::make_unique<proto::GetSumResponse>();
|
||||||
response->set_output(sum_);
|
response->set_output(sum_);
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
@ -63,16 +65,16 @@ class GetRunningSumHandler : public RpcHandler<Stream<proto::GetSumRequest>,
|
||||||
Stream<proto::GetSumResponse>> {
|
Stream<proto::GetSumResponse>> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.framework.proto.Math/GetRunningSum";
|
return "/cartographer.cloud.framework.proto.Math/GetRunningSum";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::GetSumRequest& request) override {
|
void OnRequest(const proto::GetSumRequest& request) override {
|
||||||
sum_ += request.input();
|
sum_ += request.input();
|
||||||
|
|
||||||
// Respond twice to demonstrate bidirectional streaming.
|
// Respond twice to demonstrate bidirectional streaming.
|
||||||
auto response = cartographer::common::make_unique<proto::GetSumResponse>();
|
auto response = common::make_unique<proto::GetSumResponse>();
|
||||||
response->set_output(sum_);
|
response->set_output(sum_);
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
response = cartographer::common::make_unique<proto::GetSumResponse>();
|
response = common::make_unique<proto::GetSumResponse>();
|
||||||
response->set_output(sum_);
|
response->set_output(sum_);
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
@ -87,11 +89,10 @@ class GetSquareHandler
|
||||||
: public RpcHandler<proto::GetSquareRequest, proto::GetSquareResponse> {
|
: public RpcHandler<proto::GetSquareRequest, proto::GetSquareResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.framework.proto.Math/GetSquare";
|
return "/cartographer.cloud.framework.proto.Math/GetSquare";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::GetSquareRequest& request) override {
|
void OnRequest(const proto::GetSquareRequest& request) override {
|
||||||
auto response =
|
auto response = common::make_unique<proto::GetSquareResponse>();
|
||||||
cartographer::common::make_unique<proto::GetSquareResponse>();
|
|
||||||
response->set_output(request.input() * request.input());
|
response->set_output(request.input() * request.input());
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
@ -101,15 +102,14 @@ class GetEchoHandler
|
||||||
: public RpcHandler<proto::GetEchoRequest, proto::GetEchoResponse> {
|
: public RpcHandler<proto::GetEchoRequest, proto::GetEchoResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.framework.proto.Math/GetEcho";
|
return "/cartographer.cloud.framework.proto.Math/GetEcho";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::GetEchoRequest& request) override {
|
void OnRequest(const proto::GetEchoRequest& request) override {
|
||||||
int value = request.input();
|
int value = request.input();
|
||||||
Writer writer = GetWriter();
|
Writer writer = GetWriter();
|
||||||
GetContext<MathServerContext>()->echo_responder.set_value(
|
GetContext<MathServerContext>()->echo_responder.set_value(
|
||||||
[writer, value]() {
|
[writer, value]() {
|
||||||
auto response =
|
auto response = common::make_unique<proto::GetEchoResponse>();
|
||||||
cartographer::common::make_unique<proto::GetEchoResponse>();
|
|
||||||
response->set_output(value);
|
response->set_output(value);
|
||||||
return writer.Write(std::move(response));
|
return writer.Write(std::move(response));
|
||||||
});
|
});
|
||||||
|
@ -121,12 +121,11 @@ class GetSequenceHandler
|
||||||
Stream<proto::GetSequenceResponse>> {
|
Stream<proto::GetSequenceResponse>> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.framework.proto.Math/GetSequence";
|
return "/cartographer.cloud.framework.proto.Math/GetSequence";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::GetSequenceRequest& request) override {
|
void OnRequest(const proto::GetSequenceRequest& request) override {
|
||||||
for (int i = 0; i < request.input(); ++i) {
|
for (int i = 0; i < request.input(); ++i) {
|
||||||
auto response =
|
auto response = common::make_unique<proto::GetSequenceResponse>();
|
||||||
cartographer::common::make_unique<proto::GetSequenceResponse>();
|
|
||||||
response->set_output(i);
|
response->set_output(i);
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
@ -154,12 +153,12 @@ class ServerTest : public ::testing::Test {
|
||||||
server_builder.RegisterHandler<GetSequenceHandler>();
|
server_builder.RegisterHandler<GetSequenceHandler>();
|
||||||
server_ = server_builder.Build();
|
server_ = server_builder.Build();
|
||||||
|
|
||||||
client_channel_ =
|
client_channel_ = ::grpc::CreateChannel(
|
||||||
grpc::CreateChannel(kServerAddress, grpc::InsecureChannelCredentials());
|
kServerAddress, ::grpc::InsecureChannelCredentials());
|
||||||
}
|
}
|
||||||
|
|
||||||
std::unique_ptr<Server> server_;
|
std::unique_ptr<Server> server_;
|
||||||
std::shared_ptr<grpc::Channel> client_channel_;
|
std::shared_ptr<::grpc::Channel> client_channel_;
|
||||||
};
|
};
|
||||||
|
|
||||||
TEST_F(ServerTest, StartAndStopServerTest) {
|
TEST_F(ServerTest, StartAndStopServerTest) {
|
||||||
|
@ -168,8 +167,7 @@ TEST_F(ServerTest, StartAndStopServerTest) {
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(ServerTest, ProcessRpcStreamTest) {
|
TEST_F(ServerTest, ProcessRpcStreamTest) {
|
||||||
server_->SetExecutionContext(
|
server_->SetExecutionContext(common::make_unique<MathServerContext>());
|
||||||
cartographer::common::make_unique<MathServerContext>());
|
|
||||||
server_->Start();
|
server_->Start();
|
||||||
|
|
||||||
Client<GetSumHandler> client(client_channel_);
|
Client<GetSumHandler> client(client_channel_);
|
||||||
|
@ -220,8 +218,7 @@ TEST_F(ServerTest, ProcessBidiStreamingRpcTest) {
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(ServerTest, WriteFromOtherThread) {
|
TEST_F(ServerTest, WriteFromOtherThread) {
|
||||||
server_->SetExecutionContext(
|
server_->SetExecutionContext(common::make_unique<MathServerContext>());
|
||||||
cartographer::common::make_unique<MathServerContext>());
|
|
||||||
server_->Start();
|
server_->Start();
|
||||||
|
|
||||||
Server* server = server_.get();
|
Server* server = server_.get();
|
||||||
|
@ -264,4 +261,5 @@ TEST_F(ServerTest, ProcessServerStreamingRpcTest) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
#include "grpc++/impl/codegen/proto_utils.h"
|
#include "grpc++/impl/codegen/proto_utils.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
Service::Service(const std::string& service_name,
|
Service::Service(const std::string& service_name,
|
||||||
|
@ -32,7 +33,7 @@ Service::Service(const std::string& service_name,
|
||||||
for (const auto& rpc_handler_info : rpc_handler_infos_) {
|
for (const auto& rpc_handler_info : rpc_handler_infos_) {
|
||||||
// The 'handler' below is set to 'nullptr' indicating that we want to
|
// The 'handler' below is set to 'nullptr' indicating that we want to
|
||||||
// handle this method asynchronously.
|
// handle this method asynchronously.
|
||||||
this->AddMethod(new grpc::internal::RpcServiceMethod(
|
this->AddMethod(new ::grpc::internal::RpcServiceMethod(
|
||||||
rpc_handler_info.second.fully_qualified_name.c_str(),
|
rpc_handler_info.second.fully_qualified_name.c_str(),
|
||||||
rpc_handler_info.second.rpc_type, nullptr /* handler */));
|
rpc_handler_info.second.rpc_type, nullptr /* handler */));
|
||||||
}
|
}
|
||||||
|
@ -44,11 +45,10 @@ void Service::StartServing(
|
||||||
int i = 0;
|
int i = 0;
|
||||||
for (const auto& rpc_handler_info : rpc_handler_infos_) {
|
for (const auto& rpc_handler_info : rpc_handler_infos_) {
|
||||||
for (auto& completion_queue_thread : completion_queue_threads) {
|
for (auto& completion_queue_thread : completion_queue_threads) {
|
||||||
std::shared_ptr<Rpc> rpc =
|
std::shared_ptr<Rpc> rpc = active_rpcs_.Add(common::make_unique<Rpc>(
|
||||||
active_rpcs_.Add(cartographer::common::make_unique<Rpc>(
|
i, completion_queue_thread.completion_queue(),
|
||||||
i, completion_queue_thread.completion_queue(),
|
event_queue_selector_(), execution_context, rpc_handler_info.second,
|
||||||
event_queue_selector_(), execution_context,
|
this, active_rpcs_.GetWeakPtrFactory()));
|
||||||
rpc_handler_info.second, this, active_rpcs_.GetWeakPtrFactory()));
|
|
||||||
rpc->RequestNextMethodInvocation();
|
rpc->RequestNextMethodInvocation();
|
||||||
}
|
}
|
||||||
++i;
|
++i;
|
||||||
|
@ -147,4 +147,5 @@ void Service::RemoveIfNotPending(Rpc* rpc) {
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#include "cartographer_grpc/internal/framework/rpc_handler.h"
|
#include "cartographer_grpc/internal/framework/rpc_handler.h"
|
||||||
#include "grpc++/impl/codegen/service_type.h"
|
#include "grpc++/impl/codegen/service_type.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
// A 'Service' represents a generic service for gRPC asynchronous methods and is
|
// A 'Service' represents a generic service for gRPC asynchronous methods and is
|
||||||
|
@ -60,6 +61,7 @@ class Service : public ::grpc::Service {
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_SERVICE_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_SERVICE_H
|
||||||
|
|
|
@ -28,7 +28,8 @@
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
|
@ -41,8 +42,8 @@ class RpcHandlerTestServer : public Server {
|
||||||
public:
|
public:
|
||||||
RpcHandlerTestServer(std::unique_ptr<ExecutionContext> execution_context)
|
RpcHandlerTestServer(std::unique_ptr<ExecutionContext> execution_context)
|
||||||
: Server(Options{1, 1, kServerAddress}),
|
: Server(Options{1, 1, kServerAddress}),
|
||||||
channel_(grpc::CreateChannel(kServerAddress,
|
channel_(::grpc::CreateChannel(kServerAddress,
|
||||||
grpc::InsecureChannelCredentials())),
|
::grpc::InsecureChannelCredentials())),
|
||||||
client_(channel_) {
|
client_(channel_) {
|
||||||
std::string method_full_name_under_test =
|
std::string method_full_name_under_test =
|
||||||
RpcHandlerInterface::Instantiate<RpcHandlerType>()->method_name();
|
RpcHandlerInterface::Instantiate<RpcHandlerType>()->method_name();
|
||||||
|
@ -113,7 +114,7 @@ class RpcHandlerTestServer : public Server {
|
||||||
Rpc *const rpc,
|
Rpc *const rpc,
|
||||||
ExecutionContext *const execution_context) {
|
ExecutionContext *const execution_context) {
|
||||||
std::unique_ptr<RpcHandlerInterface> rpc_handler =
|
std::unique_ptr<RpcHandlerInterface> rpc_handler =
|
||||||
cartographer::common::make_unique<RpcHandlerWrapper<RpcHandlerType>>(
|
common::make_unique<RpcHandlerWrapper<RpcHandlerType>>(
|
||||||
event_callback);
|
event_callback);
|
||||||
rpc_handler->SetRpc(rpc);
|
rpc_handler->SetRpc(rpc);
|
||||||
rpc_handler->SetExecutionContext(execution_context);
|
rpc_handler->SetExecutionContext(execution_context);
|
||||||
|
@ -126,14 +127,15 @@ class RpcHandlerTestServer : public Server {
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_ptr<::grpc::Channel> channel_;
|
std::shared_ptr<::grpc::Channel> channel_;
|
||||||
cartographer_grpc::framework::Client<RpcHandlerType> client_;
|
cloud::framework::Client<RpcHandlerType> client_;
|
||||||
cartographer::common::BlockingQueue<
|
common::BlockingQueue<
|
||||||
typename RpcHandlerWrapper<RpcHandlerType>::RpcHandlerEvent>
|
typename RpcHandlerWrapper<RpcHandlerType>::RpcHandlerEvent>
|
||||||
rpc_handler_event_queue_;
|
rpc_handler_event_queue_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_TESTING_RPC_HANDLER_TEST_SERVER_H_
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_TESTING_RPC_HANDLER_TEST_SERVER_H_
|
||||||
|
|
|
@ -19,7 +19,8 @@
|
||||||
|
|
||||||
#include <functional>
|
#include <functional>
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
|
@ -53,6 +54,7 @@ class RpcHandlerWrapper : public RpcHandlerType {
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_TESTING_RPC_HANDLER_WRAPPER_H_
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_TESTING_RPC_HANDLER_WRAPPER_H_
|
||||||
|
|
|
@ -19,7 +19,8 @@
|
||||||
|
|
||||||
#include <grpc++/grpc++.h>
|
#include <grpc++/grpc++.h>
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
|
|
||||||
template <typename Request>
|
template <typename Request>
|
||||||
|
@ -42,28 +43,29 @@ using StripStream = typename Strip<Stream, T>::type;
|
||||||
|
|
||||||
template <typename Incoming, typename Outgoing>
|
template <typename Incoming, typename Outgoing>
|
||||||
struct RpcType
|
struct RpcType
|
||||||
: public std::integral_constant<grpc::internal::RpcMethod::RpcType,
|
: public std::integral_constant<::grpc::internal::RpcMethod::RpcType,
|
||||||
grpc::internal::RpcMethod::NORMAL_RPC> {};
|
::grpc::internal::RpcMethod::NORMAL_RPC> {};
|
||||||
|
|
||||||
template <typename Incoming, typename Outgoing>
|
template <typename Incoming, typename Outgoing>
|
||||||
struct RpcType<Stream<Incoming>, Outgoing>
|
struct RpcType<Stream<Incoming>, Outgoing>
|
||||||
: public std::integral_constant<
|
: public std::integral_constant<
|
||||||
grpc::internal::RpcMethod::RpcType,
|
::grpc::internal::RpcMethod::RpcType,
|
||||||
grpc::internal::RpcMethod::CLIENT_STREAMING> {};
|
::grpc::internal::RpcMethod::CLIENT_STREAMING> {};
|
||||||
|
|
||||||
template <typename Incoming, typename Outgoing>
|
template <typename Incoming, typename Outgoing>
|
||||||
struct RpcType<Incoming, Stream<Outgoing>>
|
struct RpcType<Incoming, Stream<Outgoing>>
|
||||||
: public std::integral_constant<
|
: public std::integral_constant<
|
||||||
grpc::internal::RpcMethod::RpcType,
|
::grpc::internal::RpcMethod::RpcType,
|
||||||
grpc::internal::RpcMethod::SERVER_STREAMING> {};
|
::grpc::internal::RpcMethod::SERVER_STREAMING> {};
|
||||||
|
|
||||||
template <typename Incoming, typename Outgoing>
|
template <typename Incoming, typename Outgoing>
|
||||||
struct RpcType<Stream<Incoming>, Stream<Outgoing>>
|
struct RpcType<Stream<Incoming>, Stream<Outgoing>>
|
||||||
: public std::integral_constant<grpc::internal::RpcMethod::RpcType,
|
: public std::integral_constant<
|
||||||
grpc::internal::RpcMethod::BIDI_STREAMING> {
|
::grpc::internal::RpcMethod::RpcType,
|
||||||
};
|
::grpc::internal::RpcMethod::BIDI_STREAMING> {};
|
||||||
|
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_TYPES_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_FRAMEWORK_TYPES_H
|
||||||
|
|
|
@ -18,7 +18,8 @@
|
||||||
|
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace framework {
|
namespace framework {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -40,4 +41,5 @@ TEST(TypeTraitsTest, RpcTypes) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace framework
|
} // namespace framework
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void AddFixedFramePoseDataHandler::OnRequest(
|
void AddFixedFramePoseDataHandler::OnRequest(
|
||||||
|
@ -35,18 +36,18 @@ void AddFixedFramePoseDataHandler::OnRequest(
|
||||||
// the 'MapBuilderContext'.
|
// the 'MapBuilderContext'.
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
||||||
request.sensor_metadata().trajectory_id(),
|
request.sensor_metadata().trajectory_id(),
|
||||||
cartographer::sensor::MakeDispatchable(
|
sensor::MakeDispatchable(
|
||||||
request.sensor_metadata().sensor_id(),
|
request.sensor_metadata().sensor_id(),
|
||||||
cartographer::sensor::FromProto(request.fixed_frame_pose_data())));
|
sensor::FromProto(request.fixed_frame_pose_data())));
|
||||||
|
|
||||||
// The 'BlockingQueue' in 'LocalTrajectoryUploader' is thread-safe.
|
// The 'BlockingQueue' in 'LocalTrajectoryUploader' is thread-safe.
|
||||||
// Therefore it suffices to get an unsynchronized reference to the
|
// Therefore it suffices to get an unsynchronized reference to the
|
||||||
// 'MapBuilderContext'.
|
// 'MapBuilderContext'.
|
||||||
if (GetUnsynchronizedContext<MapBuilderContextInterface>()
|
if (GetUnsynchronizedContext<MapBuilderContextInterface>()
|
||||||
->local_trajectory_uploader()) {
|
->local_trajectory_uploader()) {
|
||||||
auto data_request = cartographer::common::make_unique<
|
auto data_request =
|
||||||
proto::AddFixedFramePoseDataRequest>();
|
common::make_unique<proto::AddFixedFramePoseDataRequest>();
|
||||||
sensor::CreateAddFixedFramePoseDataRequest(
|
CreateAddFixedFramePoseDataRequest(
|
||||||
request.sensor_metadata().sensor_id(),
|
request.sensor_metadata().sensor_id(),
|
||||||
request.sensor_metadata().trajectory_id(),
|
request.sensor_metadata().trajectory_id(),
|
||||||
request.fixed_frame_pose_data(), data_request.get());
|
request.fixed_frame_pose_data(), data_request.get());
|
||||||
|
@ -57,8 +58,9 @@ void AddFixedFramePoseDataHandler::OnRequest(
|
||||||
}
|
}
|
||||||
|
|
||||||
void AddFixedFramePoseDataHandler::OnReadsDone() {
|
void AddFixedFramePoseDataHandler::OnReadsDone() {
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class AddFixedFramePoseDataHandler
|
class AddFixedFramePoseDataHandler
|
||||||
|
@ -30,13 +31,14 @@ class AddFixedFramePoseDataHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/AddFixedFramePoseData";
|
return "/cartographer.cloud.proto.MapBuilderService/AddFixedFramePoseData";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::AddFixedFramePoseDataRequest &request) override;
|
void OnRequest(const proto::AddFixedFramePoseDataRequest &request) override;
|
||||||
void OnReadsDone() override;
|
void OnReadsDone() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_FIXED_FRAME_POSE_DATA_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_FIXED_FRAME_POSE_DATA_HANDLER_H
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "google/protobuf/text_format.h"
|
#include "google/protobuf/text_format.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -82,4 +83,5 @@ TEST_F(AddFixedFramePoseDataHandlerTest, WithMockLocalSlamUploader) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void AddImuDataHandler::OnRequest(const proto::AddImuDataRequest &request) {
|
void AddImuDataHandler::OnRequest(const proto::AddImuDataRequest &request) {
|
||||||
|
@ -34,20 +35,18 @@ void AddImuDataHandler::OnRequest(const proto::AddImuDataRequest &request) {
|
||||||
// the 'MapBuilderContext'.
|
// the 'MapBuilderContext'.
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
||||||
request.sensor_metadata().trajectory_id(),
|
request.sensor_metadata().trajectory_id(),
|
||||||
cartographer::sensor::MakeDispatchable(
|
sensor::MakeDispatchable(request.sensor_metadata().sensor_id(),
|
||||||
request.sensor_metadata().sensor_id(),
|
sensor::FromProto(request.imu_data())));
|
||||||
cartographer::sensor::FromProto(request.imu_data())));
|
|
||||||
|
|
||||||
// The 'BlockingQueue' in 'LocalTrajectoryUploader' is thread-safe.
|
// The 'BlockingQueue' in 'LocalTrajectoryUploader' is thread-safe.
|
||||||
// Therefore it suffices to get an unsynchronized reference to the
|
// Therefore it suffices to get an unsynchronized reference to the
|
||||||
// 'MapBuilderContext'.
|
// 'MapBuilderContext'.
|
||||||
if (GetUnsynchronizedContext<MapBuilderContextInterface>()
|
if (GetUnsynchronizedContext<MapBuilderContextInterface>()
|
||||||
->local_trajectory_uploader()) {
|
->local_trajectory_uploader()) {
|
||||||
auto data_request =
|
auto data_request = common::make_unique<proto::AddImuDataRequest>();
|
||||||
cartographer::common::make_unique<proto::AddImuDataRequest>();
|
CreateAddImuDataRequest(request.sensor_metadata().sensor_id(),
|
||||||
sensor::CreateAddImuDataRequest(request.sensor_metadata().sensor_id(),
|
request.sensor_metadata().trajectory_id(),
|
||||||
request.sensor_metadata().trajectory_id(),
|
request.imu_data(), data_request.get());
|
||||||
request.imu_data(), data_request.get());
|
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()
|
GetUnsynchronizedContext<MapBuilderContextInterface>()
|
||||||
->local_trajectory_uploader()
|
->local_trajectory_uploader()
|
||||||
->EnqueueDataRequest(std::move(data_request));
|
->EnqueueDataRequest(std::move(data_request));
|
||||||
|
@ -55,8 +54,9 @@ void AddImuDataHandler::OnRequest(const proto::AddImuDataRequest &request) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void AddImuDataHandler::OnReadsDone() {
|
void AddImuDataHandler::OnReadsDone() {
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class AddImuDataHandler
|
class AddImuDataHandler
|
||||||
|
@ -29,13 +30,14 @@ class AddImuDataHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/AddImuData";
|
return "/cartographer.cloud.proto.MapBuilderService/AddImuData";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::AddImuDataRequest &request) override;
|
void OnRequest(const proto::AddImuDataRequest &request) override;
|
||||||
void OnReadsDone() override;
|
void OnReadsDone() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_IMU_DATA_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_IMU_DATA_HANDLER_H
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "google/protobuf/text_format.h"
|
#include "google/protobuf/text_format.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -79,4 +80,5 @@ TEST_F(AddImuDataHandlerTest, WithMockLocalSlamUploader) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void AddLandmarkDataHandler::OnRequest(
|
void AddLandmarkDataHandler::OnRequest(
|
||||||
|
@ -35,21 +36,18 @@ void AddLandmarkDataHandler::OnRequest(
|
||||||
// the 'MapBuilderContext'.
|
// the 'MapBuilderContext'.
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
||||||
request.sensor_metadata().trajectory_id(),
|
request.sensor_metadata().trajectory_id(),
|
||||||
cartographer::sensor::MakeDispatchable(
|
sensor::MakeDispatchable(request.sensor_metadata().sensor_id(),
|
||||||
request.sensor_metadata().sensor_id(),
|
sensor::FromProto(request.landmark_data())));
|
||||||
cartographer::sensor::FromProto(request.landmark_data())));
|
|
||||||
|
|
||||||
// The 'BlockingQueue' in 'LocalTrajectoryUploader' is thread-safe.
|
// The 'BlockingQueue' in 'LocalTrajectoryUploader' is thread-safe.
|
||||||
// Therefore it suffices to get an unsynchronized reference to the
|
// Therefore it suffices to get an unsynchronized reference to the
|
||||||
// 'MapBuilderContext'.
|
// 'MapBuilderContext'.
|
||||||
if (GetUnsynchronizedContext<MapBuilderContextInterface>()
|
if (GetUnsynchronizedContext<MapBuilderContextInterface>()
|
||||||
->local_trajectory_uploader()) {
|
->local_trajectory_uploader()) {
|
||||||
auto data_request =
|
auto data_request = common::make_unique<proto::AddLandmarkDataRequest>();
|
||||||
cartographer::common::make_unique<proto::AddLandmarkDataRequest>();
|
CreateAddLandmarkDataRequest(request.sensor_metadata().sensor_id(),
|
||||||
sensor::CreateAddLandmarkDataRequest(
|
request.sensor_metadata().trajectory_id(),
|
||||||
request.sensor_metadata().sensor_id(),
|
request.landmark_data(), data_request.get());
|
||||||
request.sensor_metadata().trajectory_id(), request.landmark_data(),
|
|
||||||
data_request.get());
|
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()
|
GetUnsynchronizedContext<MapBuilderContextInterface>()
|
||||||
->local_trajectory_uploader()
|
->local_trajectory_uploader()
|
||||||
->EnqueueDataRequest(std::move(data_request));
|
->EnqueueDataRequest(std::move(data_request));
|
||||||
|
@ -57,8 +55,9 @@ void AddLandmarkDataHandler::OnRequest(
|
||||||
}
|
}
|
||||||
|
|
||||||
void AddLandmarkDataHandler::OnReadsDone() {
|
void AddLandmarkDataHandler::OnReadsDone() {
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class AddLandmarkDataHandler
|
class AddLandmarkDataHandler
|
||||||
|
@ -30,13 +31,14 @@ class AddLandmarkDataHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/AddLandmarkData";
|
return "/cartographer.cloud.proto.MapBuilderService/AddLandmarkData";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::AddLandmarkDataRequest &request) override;
|
void OnRequest(const proto::AddLandmarkDataRequest &request) override;
|
||||||
void OnReadsDone() override;
|
void OnReadsDone() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_LANDMARK_DATA_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_LANDMARK_DATA_HANDLER_H
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "google/protobuf/text_format.h"
|
#include "google/protobuf/text_format.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -86,4 +87,5 @@ TEST_F(AddLandmarkDataHandlerTest, WithMockLocalSlamUploader) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void AddLocalSlamResultDataHandler::OnRequest(
|
void AddLocalSlamResultDataHandler::OnRequest(
|
||||||
|
@ -33,8 +34,7 @@ void AddLocalSlamResultDataHandler::OnRequest(
|
||||||
auto local_slam_result_data =
|
auto local_slam_result_data =
|
||||||
GetContext<MapBuilderContextInterface>()->ProcessLocalSlamResultData(
|
GetContext<MapBuilderContextInterface>()->ProcessLocalSlamResultData(
|
||||||
request.sensor_metadata().sensor_id(),
|
request.sensor_metadata().sensor_id(),
|
||||||
cartographer::common::FromUniversal(
|
common::FromUniversal(request.local_slam_result_data().timestamp()),
|
||||||
request.local_slam_result_data().timestamp()),
|
|
||||||
request.local_slam_result_data());
|
request.local_slam_result_data());
|
||||||
GetContext<MapBuilderContextInterface>()->EnqueueLocalSlamResultData(
|
GetContext<MapBuilderContextInterface>()->EnqueueLocalSlamResultData(
|
||||||
request.sensor_metadata().trajectory_id(),
|
request.sensor_metadata().trajectory_id(),
|
||||||
|
@ -42,8 +42,9 @@ void AddLocalSlamResultDataHandler::OnRequest(
|
||||||
}
|
}
|
||||||
|
|
||||||
void AddLocalSlamResultDataHandler::OnReadsDone() {
|
void AddLocalSlamResultDataHandler::OnReadsDone() {
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class AddLocalSlamResultDataHandler
|
class AddLocalSlamResultDataHandler
|
||||||
|
@ -30,13 +31,14 @@ class AddLocalSlamResultDataHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/AddLocalSlamResultData";
|
return "/cartographer.cloud.proto.MapBuilderService/AddLocalSlamResultData";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::AddLocalSlamResultDataRequest& request) override;
|
void OnRequest(const proto::AddLocalSlamResultDataRequest& request) override;
|
||||||
void OnReadsDone() override;
|
void OnReadsDone() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_LOCAL_SLAM_RESULT_DATA_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_LOCAL_SLAM_RESULT_DATA_HANDLER_H
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void AddOdometryDataHandler::OnRequest(
|
void AddOdometryDataHandler::OnRequest(
|
||||||
|
@ -35,21 +36,18 @@ void AddOdometryDataHandler::OnRequest(
|
||||||
// the 'MapBuilderContext'.
|
// the 'MapBuilderContext'.
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
||||||
request.sensor_metadata().trajectory_id(),
|
request.sensor_metadata().trajectory_id(),
|
||||||
cartographer::sensor::MakeDispatchable(
|
sensor::MakeDispatchable(request.sensor_metadata().sensor_id(),
|
||||||
request.sensor_metadata().sensor_id(),
|
sensor::FromProto(request.odometry_data())));
|
||||||
cartographer::sensor::FromProto(request.odometry_data())));
|
|
||||||
|
|
||||||
// The 'BlockingQueue' in 'LocalTrajectoryUploader' is thread-safe.
|
// The 'BlockingQueue' in 'LocalTrajectoryUploader' is thread-safe.
|
||||||
// Therefore it suffices to get an unsynchronized reference to the
|
// Therefore it suffices to get an unsynchronized reference to the
|
||||||
// 'MapBuilderContext'.
|
// 'MapBuilderContext'.
|
||||||
if (GetUnsynchronizedContext<MapBuilderContextInterface>()
|
if (GetUnsynchronizedContext<MapBuilderContextInterface>()
|
||||||
->local_trajectory_uploader()) {
|
->local_trajectory_uploader()) {
|
||||||
auto data_request =
|
auto data_request = common::make_unique<proto::AddOdometryDataRequest>();
|
||||||
cartographer::common::make_unique<proto::AddOdometryDataRequest>();
|
CreateAddOdometryDataRequest(request.sensor_metadata().sensor_id(),
|
||||||
sensor::CreateAddOdometryDataRequest(
|
request.sensor_metadata().trajectory_id(),
|
||||||
request.sensor_metadata().sensor_id(),
|
request.odometry_data(), data_request.get());
|
||||||
request.sensor_metadata().trajectory_id(), request.odometry_data(),
|
|
||||||
data_request.get());
|
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()
|
GetUnsynchronizedContext<MapBuilderContextInterface>()
|
||||||
->local_trajectory_uploader()
|
->local_trajectory_uploader()
|
||||||
->EnqueueDataRequest(std::move(data_request));
|
->EnqueueDataRequest(std::move(data_request));
|
||||||
|
@ -57,8 +55,9 @@ void AddOdometryDataHandler::OnRequest(
|
||||||
}
|
}
|
||||||
|
|
||||||
void AddOdometryDataHandler::OnReadsDone() {
|
void AddOdometryDataHandler::OnReadsDone() {
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class AddOdometryDataHandler
|
class AddOdometryDataHandler
|
||||||
|
@ -30,13 +31,14 @@ class AddOdometryDataHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/AddOdometryData";
|
return "/cartographer.cloud.proto.MapBuilderService/AddOdometryData";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::AddOdometryDataRequest &request) override;
|
void OnRequest(const proto::AddOdometryDataRequest &request) override;
|
||||||
void OnReadsDone() override;
|
void OnReadsDone() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_ODOMETRY_DATA_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_ODOMETRY_DATA_HANDLER_H
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "google/protobuf/text_format.h"
|
#include "google/protobuf/text_format.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -81,4 +82,5 @@ TEST_F(AddOdometryDataHandlerTest, WithMockLocalSlamUploader) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void AddRangefinderDataHandler::OnRequest(
|
void AddRangefinderDataHandler::OnRequest(
|
||||||
|
@ -34,14 +35,15 @@ void AddRangefinderDataHandler::OnRequest(
|
||||||
// the 'MapBuilderContext'.
|
// the 'MapBuilderContext'.
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
GetUnsynchronizedContext<MapBuilderContextInterface>()->EnqueueSensorData(
|
||||||
request.sensor_metadata().trajectory_id(),
|
request.sensor_metadata().trajectory_id(),
|
||||||
cartographer::sensor::MakeDispatchable(
|
sensor::MakeDispatchable(
|
||||||
request.sensor_metadata().sensor_id(),
|
request.sensor_metadata().sensor_id(),
|
||||||
cartographer::sensor::FromProto(request.timed_point_cloud_data())));
|
sensor::FromProto(request.timed_point_cloud_data())));
|
||||||
}
|
}
|
||||||
|
|
||||||
void AddRangefinderDataHandler::OnReadsDone() {
|
void AddRangefinderDataHandler::OnReadsDone() {
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class AddRangefinderDataHandler
|
class AddRangefinderDataHandler
|
||||||
|
@ -30,13 +31,14 @@ class AddRangefinderDataHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/AddRangefinderData";
|
return "/cartographer.cloud.proto.MapBuilderService/AddRangefinderData";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::AddRangefinderDataRequest &request) override;
|
void OnRequest(const proto::AddRangefinderDataRequest &request) override;
|
||||||
void OnReadsDone() override;
|
void OnReadsDone() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_RANGEFINDER_DATA_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_RANGEFINDER_DATA_HANDLER_H
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "google/protobuf/text_format.h"
|
#include "google/protobuf/text_format.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -62,4 +63,5 @@ TEST_F(AddRangefinderDataHandlerTest, NoLocalSlamUploader) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "cartographer_grpc/internal/sensor/serialization.h"
|
#include "cartographer_grpc/internal/sensor/serialization.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void AddTrajectoryHandler::OnRequest(
|
void AddTrajectoryHandler::OnRequest(
|
||||||
|
@ -30,10 +31,9 @@ void AddTrajectoryHandler::OnRequest(
|
||||||
auto local_slam_result_callback =
|
auto local_slam_result_callback =
|
||||||
GetUnsynchronizedContext<MapBuilderContextInterface>()
|
GetUnsynchronizedContext<MapBuilderContextInterface>()
|
||||||
->GetLocalSlamResultCallbackForSubscriptions();
|
->GetLocalSlamResultCallbackForSubscriptions();
|
||||||
std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>
|
std::set<mapping::TrajectoryBuilderInterface::SensorId> expected_sensor_ids;
|
||||||
expected_sensor_ids;
|
|
||||||
for (const auto& sensor_id : request.expected_sensor_ids()) {
|
for (const auto& sensor_id : request.expected_sensor_ids()) {
|
||||||
expected_sensor_ids.insert(sensor::FromProto(sensor_id));
|
expected_sensor_ids.insert(FromProto(sensor_id));
|
||||||
}
|
}
|
||||||
const int trajectory_id =
|
const int trajectory_id =
|
||||||
GetContext<MapBuilderContextInterface>()
|
GetContext<MapBuilderContextInterface>()
|
||||||
|
@ -61,11 +61,11 @@ void AddTrajectoryHandler::OnRequest(
|
||||||
trajectory_builder_options);
|
trajectory_builder_options);
|
||||||
}
|
}
|
||||||
|
|
||||||
auto response =
|
auto response = common::make_unique<proto::AddTrajectoryResponse>();
|
||||||
cartographer::common::make_unique<proto::AddTrajectoryResponse>();
|
|
||||||
response->set_trajectory_id(trajectory_id);
|
response->set_trajectory_id(trajectory_id);
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "cartographer_grpc/internal/framework/rpc_handler.h"
|
#include "cartographer_grpc/internal/framework/rpc_handler.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class AddTrajectoryHandler
|
class AddTrajectoryHandler
|
||||||
|
@ -28,12 +29,13 @@ class AddTrajectoryHandler
|
||||||
proto::AddTrajectoryResponse> {
|
proto::AddTrajectoryResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/AddTrajectory";
|
return "/cartographer.cloud.proto.MapBuilderService/AddTrajectory";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::AddTrajectoryRequest& request) override;
|
void OnRequest(const proto::AddTrajectoryRequest& request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_TRAJECTORY_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_ADD_TRAJECTORY_HANDLER_H
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "google/protobuf/text_format.h"
|
#include "google/protobuf/text_format.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -69,8 +70,7 @@ class AddTrajectoryHandlerTest
|
||||||
public:
|
public:
|
||||||
void SetUp() override {
|
void SetUp() override {
|
||||||
testing::HandlerTest<AddTrajectoryHandler>::SetUp();
|
testing::HandlerTest<AddTrajectoryHandler>::SetUp();
|
||||||
mock_map_builder_ =
|
mock_map_builder_ = common::make_unique<testing::MockMapBuilder>();
|
||||||
cartographer::common::make_unique<testing::MockMapBuilder>();
|
|
||||||
EXPECT_CALL(*mock_map_builder_context_,
|
EXPECT_CALL(*mock_map_builder_context_,
|
||||||
GetLocalSlamResultCallbackForSubscriptions())
|
GetLocalSlamResultCallbackForSubscriptions())
|
||||||
.WillOnce(Return(nullptr));
|
.WillOnce(Return(nullptr));
|
||||||
|
@ -79,12 +79,11 @@ class AddTrajectoryHandlerTest
|
||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>
|
std::set<mapping::TrajectoryBuilderInterface::SensorId> ParseSensorIds(
|
||||||
ParseSensorIds(const proto::AddTrajectoryRequest &request) {
|
const proto::AddTrajectoryRequest &request) {
|
||||||
std::set<cartographer::mapping::TrajectoryBuilderInterface::SensorId>
|
std::set<mapping::TrajectoryBuilderInterface::SensorId> expected_sensor_ids;
|
||||||
expected_sensor_ids;
|
|
||||||
for (const auto &sensor_id : request.expected_sensor_ids()) {
|
for (const auto &sensor_id : request.expected_sensor_ids()) {
|
||||||
expected_sensor_ids.insert(sensor::FromProto(sensor_id));
|
expected_sensor_ids.insert(cloud::FromProto(sensor_id));
|
||||||
}
|
}
|
||||||
return expected_sensor_ids;
|
return expected_sensor_ids;
|
||||||
}
|
}
|
||||||
|
@ -133,4 +132,5 @@ TEST_F(AddTrajectoryHandlerTest, WithLocalSlamUploader) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void FinishTrajectoryHandler::OnRequest(
|
void FinishTrajectoryHandler::OnRequest(
|
||||||
|
@ -37,8 +38,9 @@ void FinishTrajectoryHandler::OnRequest(
|
||||||
->local_trajectory_uploader()
|
->local_trajectory_uploader()
|
||||||
->FinishTrajectory(request.trajectory_id());
|
->FinishTrajectory(request.trajectory_id());
|
||||||
}
|
}
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class FinishTrajectoryHandler
|
class FinishTrajectoryHandler
|
||||||
|
@ -29,12 +30,13 @@ class FinishTrajectoryHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/FinishTrajectory";
|
return "/cartographer.cloud.proto.MapBuilderService/FinishTrajectory";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::FinishTrajectoryRequest& request) override;
|
void OnRequest(const proto::FinishTrajectoryRequest& request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_FINISH_TRAJECTORY_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_FINISH_TRAJECTORY_HANDLER_H
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void GetAllSubmapPosesHandler::OnRequest(
|
void GetAllSubmapPosesHandler::OnRequest(
|
||||||
|
@ -31,17 +32,17 @@ void GetAllSubmapPosesHandler::OnRequest(
|
||||||
->map_builder()
|
->map_builder()
|
||||||
.pose_graph()
|
.pose_graph()
|
||||||
->GetAllSubmapPoses();
|
->GetAllSubmapPoses();
|
||||||
auto response =
|
auto response = common::make_unique<proto::GetAllSubmapPosesResponse>();
|
||||||
cartographer::common::make_unique<proto::GetAllSubmapPosesResponse>();
|
|
||||||
for (const auto& submap_id_pose : submap_poses) {
|
for (const auto& submap_id_pose : submap_poses) {
|
||||||
auto* submap_pose = response->add_submap_poses();
|
auto* submap_pose = response->add_submap_poses();
|
||||||
submap_id_pose.id.ToProto(submap_pose->mutable_submap_id());
|
submap_id_pose.id.ToProto(submap_pose->mutable_submap_id());
|
||||||
submap_pose->set_submap_version(submap_id_pose.data.version);
|
submap_pose->set_submap_version(submap_id_pose.data.version);
|
||||||
*submap_pose->mutable_global_pose() =
|
*submap_pose->mutable_global_pose() =
|
||||||
cartographer::transform::ToProto(submap_id_pose.data.pose);
|
transform::ToProto(submap_id_pose.data.pose);
|
||||||
}
|
}
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class GetAllSubmapPosesHandler
|
class GetAllSubmapPosesHandler
|
||||||
|
@ -29,12 +30,13 @@ class GetAllSubmapPosesHandler
|
||||||
proto::GetAllSubmapPosesResponse> {
|
proto::GetAllSubmapPosesResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/GetAllSubmapPoses";
|
return "/cartographer.cloud.proto.MapBuilderService/GetAllSubmapPoses";
|
||||||
}
|
}
|
||||||
void OnRequest(const google::protobuf::Empty& request) override;
|
void OnRequest(const google::protobuf::Empty& request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_ALL_SUBMAP_POSES_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_ALL_SUBMAP_POSES_H
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void GetConstraintsHandler::OnRequest(const google::protobuf::Empty& request) {
|
void GetConstraintsHandler::OnRequest(const google::protobuf::Empty& request) {
|
||||||
|
@ -31,14 +32,14 @@ void GetConstraintsHandler::OnRequest(const google::protobuf::Empty& request) {
|
||||||
->map_builder()
|
->map_builder()
|
||||||
.pose_graph()
|
.pose_graph()
|
||||||
->constraints();
|
->constraints();
|
||||||
auto response =
|
auto response = common::make_unique<proto::GetConstraintsResponse>();
|
||||||
cartographer::common::make_unique<proto::GetConstraintsResponse>();
|
|
||||||
response->mutable_constraints()->Reserve(constraints.size());
|
response->mutable_constraints()->Reserve(constraints.size());
|
||||||
for (const auto& constraint : constraints) {
|
for (const auto& constraint : constraints) {
|
||||||
*response->add_constraints() = cartographer::mapping::ToProto(constraint);
|
*response->add_constraints() = mapping::ToProto(constraint);
|
||||||
}
|
}
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class GetConstraintsHandler
|
class GetConstraintsHandler
|
||||||
|
@ -29,12 +30,13 @@ class GetConstraintsHandler
|
||||||
proto::GetConstraintsResponse> {
|
proto::GetConstraintsResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/GetConstraints";
|
return "/cartographer.cloud.proto.MapBuilderService/GetConstraints";
|
||||||
}
|
}
|
||||||
void OnRequest(const google::protobuf::Empty& request) override;
|
void OnRequest(const google::protobuf::Empty& request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_CONSTRAINTS_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_CONSTRAINTS_HANDLER_H
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void GetLandmarkPosesHandler::OnRequest(
|
void GetLandmarkPosesHandler::OnRequest(
|
||||||
|
@ -31,16 +32,15 @@ void GetLandmarkPosesHandler::OnRequest(
|
||||||
->map_builder()
|
->map_builder()
|
||||||
.pose_graph()
|
.pose_graph()
|
||||||
->GetLandmarkPoses();
|
->GetLandmarkPoses();
|
||||||
auto response =
|
auto response = common::make_unique<proto::GetLandmarkPosesResponse>();
|
||||||
cartographer::common::make_unique<proto::GetLandmarkPosesResponse>();
|
|
||||||
for (const auto& landmark_pose : landmark_poses) {
|
for (const auto& landmark_pose : landmark_poses) {
|
||||||
auto* landmark = response->add_landmark_poses();
|
auto* landmark = response->add_landmark_poses();
|
||||||
landmark->set_landmark_id(landmark_pose.first);
|
landmark->set_landmark_id(landmark_pose.first);
|
||||||
*landmark->mutable_global_pose() =
|
*landmark->mutable_global_pose() = transform::ToProto(landmark_pose.second);
|
||||||
cartographer::transform::ToProto(landmark_pose.second);
|
|
||||||
}
|
}
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class GetLandmarkPosesHandler
|
class GetLandmarkPosesHandler
|
||||||
|
@ -29,12 +30,13 @@ class GetLandmarkPosesHandler
|
||||||
proto::GetLandmarkPosesResponse> {
|
proto::GetLandmarkPosesResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/GetLandmarkPoses";
|
return "/cartographer.cloud.proto.MapBuilderService/GetLandmarkPoses";
|
||||||
}
|
}
|
||||||
void OnRequest(const google::protobuf::Empty& request) override;
|
void OnRequest(const google::protobuf::Empty& request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_LANDMARK_POSES_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_LANDMARK_POSES_HANDLER_H
|
||||||
|
|
|
@ -20,7 +20,8 @@
|
||||||
#include "google/protobuf/text_format.h"
|
#include "google/protobuf/text_format.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
|
@ -78,4 +79,5 @@ TEST_F(GetLandmarkPosesHandlerTest, NoLocalSlamUploader) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,22 +21,23 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void GetLocalToGlobalTransformHandler::OnRequest(
|
void GetLocalToGlobalTransformHandler::OnRequest(
|
||||||
const proto::GetLocalToGlobalTransformRequest& request) {
|
const proto::GetLocalToGlobalTransformRequest& request) {
|
||||||
auto response = cartographer::common::make_unique<
|
auto response =
|
||||||
proto::GetLocalToGlobalTransformResponse>();
|
common::make_unique<proto::GetLocalToGlobalTransformResponse>();
|
||||||
auto local_to_global =
|
auto local_to_global =
|
||||||
GetContext<MapBuilderContextInterface>()
|
GetContext<MapBuilderContextInterface>()
|
||||||
->map_builder()
|
->map_builder()
|
||||||
.pose_graph()
|
.pose_graph()
|
||||||
->GetLocalToGlobalTransform(request.trajectory_id());
|
->GetLocalToGlobalTransform(request.trajectory_id());
|
||||||
*response->mutable_local_to_global() =
|
*response->mutable_local_to_global() = transform::ToProto(local_to_global);
|
||||||
cartographer::transform::ToProto(local_to_global);
|
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class GetLocalToGlobalTransformHandler
|
class GetLocalToGlobalTransformHandler
|
||||||
|
@ -29,7 +30,7 @@ class GetLocalToGlobalTransformHandler
|
||||||
proto::GetLocalToGlobalTransformResponse> {
|
proto::GetLocalToGlobalTransformResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/"
|
return "/cartographer.cloud.proto.MapBuilderService/"
|
||||||
"GetLocalToGlobalTransform";
|
"GetLocalToGlobalTransform";
|
||||||
}
|
}
|
||||||
void OnRequest(
|
void OnRequest(
|
||||||
|
@ -37,6 +38,7 @@ class GetLocalToGlobalTransformHandler
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_LOCAL_TO_GLOBAL_TRANSFORM_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_LOCAL_TO_GLOBAL_TRANSFORM_HANDLER_H
|
||||||
|
|
|
@ -22,18 +22,20 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void GetSubmapHandler::OnRequest(const proto::GetSubmapRequest &request) {
|
void GetSubmapHandler::OnRequest(const proto::GetSubmapRequest &request) {
|
||||||
auto response = cartographer::common::make_unique<proto::GetSubmapResponse>();
|
auto response = common::make_unique<proto::GetSubmapResponse>();
|
||||||
response->set_error_msg(
|
response->set_error_msg(
|
||||||
GetContext<MapBuilderContextInterface>()->map_builder().SubmapToProto(
|
GetContext<MapBuilderContextInterface>()->map_builder().SubmapToProto(
|
||||||
cartographer::mapping::SubmapId{request.submap_id().trajectory_id(),
|
mapping::SubmapId{request.submap_id().trajectory_id(),
|
||||||
request.submap_id().submap_index()},
|
request.submap_id().submap_index()},
|
||||||
response->mutable_submap_query_response()));
|
response->mutable_submap_query_response()));
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class GetSubmapHandler
|
class GetSubmapHandler
|
||||||
|
@ -29,12 +30,13 @@ class GetSubmapHandler
|
||||||
proto::GetSubmapResponse> {
|
proto::GetSubmapResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/GetSubmap";
|
return "/cartographer.cloud.proto.MapBuilderService/GetSubmap";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::GetSubmapRequest &request) override;
|
void OnRequest(const proto::GetSubmapRequest &request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_SUBMAP_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_SUBMAP_HANDLER_H
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void GetTrajectoryNodePosesHandler::OnRequest(
|
void GetTrajectoryNodePosesHandler::OnRequest(
|
||||||
|
@ -31,17 +32,17 @@ void GetTrajectoryNodePosesHandler::OnRequest(
|
||||||
->map_builder()
|
->map_builder()
|
||||||
.pose_graph()
|
.pose_graph()
|
||||||
->GetTrajectoryNodePoses();
|
->GetTrajectoryNodePoses();
|
||||||
auto response = cartographer::common::make_unique<
|
auto response = common::make_unique<proto::GetTrajectoryNodePosesResponse>();
|
||||||
proto::GetTrajectoryNodePosesResponse>();
|
|
||||||
for (const auto& node_id_pose : node_poses) {
|
for (const auto& node_id_pose : node_poses) {
|
||||||
auto* node_pose = response->add_node_poses();
|
auto* node_pose = response->add_node_poses();
|
||||||
node_id_pose.id.ToProto(node_pose->mutable_node_id());
|
node_id_pose.id.ToProto(node_pose->mutable_node_id());
|
||||||
*node_pose->mutable_global_pose() =
|
*node_pose->mutable_global_pose() =
|
||||||
cartographer::transform::ToProto(node_id_pose.data.global_pose);
|
transform::ToProto(node_id_pose.data.global_pose);
|
||||||
node_pose->set_has_constant_data(node_id_pose.data.has_constant_data);
|
node_pose->set_has_constant_data(node_id_pose.data.has_constant_data);
|
||||||
}
|
}
|
||||||
Send(std::move(response));
|
Send(std::move(response));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class GetTrajectoryNodePosesHandler
|
class GetTrajectoryNodePosesHandler
|
||||||
|
@ -29,12 +30,13 @@ class GetTrajectoryNodePosesHandler
|
||||||
proto::GetTrajectoryNodePosesResponse> {
|
proto::GetTrajectoryNodePosesResponse> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/GetTrajectoryNodePoses";
|
return "/cartographer.cloud.proto.MapBuilderService/GetTrajectoryNodePoses";
|
||||||
}
|
}
|
||||||
void OnRequest(const google::protobuf::Empty& request) override;
|
void OnRequest(const google::protobuf::Empty& request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_TRAJECTORY_NODE_POSES_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_GET_TRAJECTORY_NODE_POSES_HANDLER_H
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void LoadStateHandler::OnRequest(const proto::LoadStateRequest& request) {
|
void LoadStateHandler::OnRequest(const proto::LoadStateRequest& request) {
|
||||||
|
@ -45,8 +46,9 @@ void LoadStateHandler::OnRequest(const proto::LoadStateRequest& request) {
|
||||||
void LoadStateHandler::OnReadsDone() {
|
void LoadStateHandler::OnReadsDone() {
|
||||||
GetContext<MapBuilderContextInterface>()->map_builder().LoadState(&reader_,
|
GetContext<MapBuilderContextInterface>()->map_builder().LoadState(&reader_,
|
||||||
true);
|
true);
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class LoadStateHandler
|
class LoadStateHandler
|
||||||
|
@ -30,16 +31,17 @@ class LoadStateHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/LoadState";
|
return "/cartographer.cloud.proto.MapBuilderService/LoadState";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::LoadStateRequest& request) override;
|
void OnRequest(const proto::LoadStateRequest& request) override;
|
||||||
void OnReadsDone() override;
|
void OnReadsDone() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
cartographer::io::InMemoryProtoStreamReader reader_;
|
io::InMemoryProtoStreamReader reader_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_LOAD_STATE_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_LOAD_STATE_HANDLER_H
|
||||||
|
|
|
@ -21,23 +21,22 @@
|
||||||
#include "cartographer_grpc/internal/map_builder_context_interface.h"
|
#include "cartographer_grpc/internal/map_builder_context_interface.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
std::unique_ptr<proto::ReceiveLocalSlamResultsResponse> GenerateResponse(
|
std::unique_ptr<proto::ReceiveLocalSlamResultsResponse> GenerateResponse(
|
||||||
std::unique_ptr<MapBuilderContextInterface::LocalSlamResult>
|
std::unique_ptr<MapBuilderContextInterface::LocalSlamResult>
|
||||||
local_slam_result) {
|
local_slam_result) {
|
||||||
auto response = cartographer::common::make_unique<
|
auto response = common::make_unique<proto::ReceiveLocalSlamResultsResponse>();
|
||||||
proto::ReceiveLocalSlamResultsResponse>();
|
|
||||||
response->set_trajectory_id(local_slam_result->trajectory_id);
|
response->set_trajectory_id(local_slam_result->trajectory_id);
|
||||||
response->set_timestamp(
|
response->set_timestamp(common::ToUniversal(local_slam_result->time));
|
||||||
cartographer::common::ToUniversal(local_slam_result->time));
|
|
||||||
*response->mutable_local_pose() =
|
*response->mutable_local_pose() =
|
||||||
cartographer::transform::ToProto(local_slam_result->local_pose);
|
transform::ToProto(local_slam_result->local_pose);
|
||||||
if (local_slam_result->range_data) {
|
if (local_slam_result->range_data) {
|
||||||
*response->mutable_range_data() =
|
*response->mutable_range_data() =
|
||||||
cartographer::sensor::ToProto(*local_slam_result->range_data);
|
sensor::ToProto(*local_slam_result->range_data);
|
||||||
}
|
}
|
||||||
if (local_slam_result->insertion_result) {
|
if (local_slam_result->insertion_result) {
|
||||||
local_slam_result->insertion_result->node_id.ToProto(
|
local_slam_result->insertion_result->node_id.ToProto(
|
||||||
|
@ -67,8 +66,9 @@ void ReceiveLocalSlamResultsHandler::OnRequest(
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
subscription_id_ = cartographer::common::make_unique<
|
subscription_id_ =
|
||||||
MapBuilderContextInterface::SubscriptionId>(subscription_id);
|
common::make_unique<MapBuilderContextInterface::SubscriptionId>(
|
||||||
|
subscription_id);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ReceiveLocalSlamResultsHandler::OnFinish() {
|
void ReceiveLocalSlamResultsHandler::OnFinish() {
|
||||||
|
@ -79,4 +79,5 @@ void ReceiveLocalSlamResultsHandler::OnFinish() {
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -23,7 +23,8 @@
|
||||||
#include "cartographer_grpc/internal/map_builder_context_interface.h"
|
#include "cartographer_grpc/internal/map_builder_context_interface.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class ReceiveLocalSlamResultsHandler
|
class ReceiveLocalSlamResultsHandler
|
||||||
|
@ -32,7 +33,8 @@ class ReceiveLocalSlamResultsHandler
|
||||||
framework::Stream<proto::ReceiveLocalSlamResultsResponse>> {
|
framework::Stream<proto::ReceiveLocalSlamResultsResponse>> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/ReceiveLocalSlamResults";
|
return "/cartographer.cloud.proto.MapBuilderService/"
|
||||||
|
"ReceiveLocalSlamResults";
|
||||||
}
|
}
|
||||||
void OnRequest(const proto::ReceiveLocalSlamResultsRequest& request) override;
|
void OnRequest(const proto::ReceiveLocalSlamResultsRequest& request) override;
|
||||||
void OnFinish() override;
|
void OnFinish() override;
|
||||||
|
@ -42,6 +44,7 @@ class ReceiveLocalSlamResultsHandler
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_RECEIVE_LOCAL_SLAM_RESULTS_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_RECEIVE_LOCAL_SLAM_RESULTS_HANDLER_H
|
||||||
|
|
|
@ -24,7 +24,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void RunFinalOptimizationHandler::OnRequest(
|
void RunFinalOptimizationHandler::OnRequest(
|
||||||
|
@ -33,8 +34,9 @@ void RunFinalOptimizationHandler::OnRequest(
|
||||||
->map_builder()
|
->map_builder()
|
||||||
.pose_graph()
|
.pose_graph()
|
||||||
->RunFinalOptimization();
|
->RunFinalOptimization();
|
||||||
Send(cartographer::common::make_unique<google::protobuf::Empty>());
|
Send(common::make_unique<google::protobuf::Empty>());
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class RunFinalOptimizationHandler
|
class RunFinalOptimizationHandler
|
||||||
|
@ -29,12 +30,13 @@ class RunFinalOptimizationHandler
|
||||||
google::protobuf::Empty> {
|
google::protobuf::Empty> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/RunFinalOptimization";
|
return "/cartographer.cloud.proto.MapBuilderService/RunFinalOptimization";
|
||||||
}
|
}
|
||||||
void OnRequest(const google::protobuf::Empty& request) override;
|
void OnRequest(const google::protobuf::Empty& request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_RUN_FINAL_OPTIMIZATION_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_RUN_FINAL_OPTIMIZATION_H
|
||||||
|
|
|
@ -23,20 +23,20 @@
|
||||||
#include "cartographer_grpc/internal/map_builder_server.h"
|
#include "cartographer_grpc/internal/map_builder_server.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
void WriteStateHandler::OnRequest(const google::protobuf::Empty& request) {
|
void WriteStateHandler::OnRequest(const google::protobuf::Empty& request) {
|
||||||
auto writer = GetWriter();
|
auto writer = GetWriter();
|
||||||
cartographer::io::ForwardingProtoStreamWriter proto_stream_writer(
|
io::ForwardingProtoStreamWriter proto_stream_writer(
|
||||||
[writer](const google::protobuf::Message* proto) {
|
[writer](const google::protobuf::Message* proto) {
|
||||||
if (!proto) {
|
if (!proto) {
|
||||||
writer.WritesDone();
|
writer.WritesDone();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
auto response =
|
auto response = common::make_unique<proto::WriteStateResponse>();
|
||||||
cartographer::common::make_unique<proto::WriteStateResponse>();
|
|
||||||
if (proto->GetTypeName() == "cartographer.mapping.proto.PoseGraph") {
|
if (proto->GetTypeName() == "cartographer.mapping.proto.PoseGraph") {
|
||||||
response->mutable_pose_graph()->CopyFrom(*proto);
|
response->mutable_pose_graph()->CopyFrom(*proto);
|
||||||
} else if (proto->GetTypeName() ==
|
} else if (proto->GetTypeName() ==
|
||||||
|
@ -56,4 +56,5 @@ void WriteStateHandler::OnRequest(const google::protobuf::Empty& request) {
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,7 +21,8 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/empty.pb.h"
|
#include "google/protobuf/empty.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace handlers {
|
namespace handlers {
|
||||||
|
|
||||||
class WriteStateHandler : public framework::RpcHandler<
|
class WriteStateHandler : public framework::RpcHandler<
|
||||||
|
@ -29,12 +30,13 @@ class WriteStateHandler : public framework::RpcHandler<
|
||||||
framework::Stream<proto::WriteStateResponse>> {
|
framework::Stream<proto::WriteStateResponse>> {
|
||||||
public:
|
public:
|
||||||
std::string method_name() const override {
|
std::string method_name() const override {
|
||||||
return "/cartographer_grpc.proto.MapBuilderService/WriteState";
|
return "/cartographer.cloud.proto.MapBuilderService/WriteState";
|
||||||
}
|
}
|
||||||
void OnRequest(const google::protobuf::Empty& request) override;
|
void OnRequest(const google::protobuf::Empty& request) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace handlers
|
} // namespace handlers
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_WRITE_STATE_HANDLER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_HANDLERS_WRITE_STATE_HANDLER_H
|
||||||
|
|
|
@ -33,19 +33,19 @@
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
#include "grpc++/grpc++.h"
|
#include "grpc++/grpc++.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
using ::cartographer::common::make_unique;
|
using common::make_unique;
|
||||||
|
|
||||||
const cartographer::common::Duration kPopTimeout =
|
const common::Duration kPopTimeout = common::FromMilliseconds(100);
|
||||||
cartographer::common::FromMilliseconds(100);
|
|
||||||
|
|
||||||
class LocalTrajectoryUploader : public LocalTrajectoryUploaderInterface {
|
class LocalTrajectoryUploader : public LocalTrajectoryUploaderInterface {
|
||||||
public:
|
public:
|
||||||
LocalTrajectoryUploader(const std::string &uplink_server_address)
|
LocalTrajectoryUploader(const std::string &uplink_server_address)
|
||||||
: client_channel_(grpc::CreateChannel(
|
: client_channel_(::grpc::CreateChannel(
|
||||||
uplink_server_address, grpc::InsecureChannelCredentials())) {}
|
uplink_server_address, ::grpc::InsecureChannelCredentials())) {}
|
||||||
~LocalTrajectoryUploader();
|
~LocalTrajectoryUploader();
|
||||||
|
|
||||||
// Starts the upload thread.
|
// Starts the upload thread.
|
||||||
|
@ -57,8 +57,7 @@ class LocalTrajectoryUploader : public LocalTrajectoryUploaderInterface {
|
||||||
|
|
||||||
void AddTrajectory(
|
void AddTrajectory(
|
||||||
int local_trajectory_id, const std::set<SensorId> &expected_sensor_ids,
|
int local_trajectory_id, const std::set<SensorId> &expected_sensor_ids,
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptions
|
const mapping::proto::TrajectoryBuilderOptions &trajectory_options) final;
|
||||||
&trajectory_options) final;
|
|
||||||
void FinishTrajectory(int local_trajectory_id) final;
|
void FinishTrajectory(int local_trajectory_id) final;
|
||||||
void EnqueueDataRequest(
|
void EnqueueDataRequest(
|
||||||
std::unique_ptr<google::protobuf::Message> data_request) final;
|
std::unique_ptr<google::protobuf::Message> data_request) final;
|
||||||
|
@ -79,11 +78,9 @@ class LocalTrajectoryUploader : public LocalTrajectoryUploaderInterface {
|
||||||
void ProcessOdometryDataMessage(proto::AddOdometryDataRequest *data_request);
|
void ProcessOdometryDataMessage(proto::AddOdometryDataRequest *data_request);
|
||||||
void ProcessLandmarkDataMessage(proto::AddLandmarkDataRequest *data_request);
|
void ProcessLandmarkDataMessage(proto::AddLandmarkDataRequest *data_request);
|
||||||
|
|
||||||
std::shared_ptr<grpc::Channel> client_channel_;
|
std::shared_ptr<::grpc::Channel> client_channel_;
|
||||||
std::map<int, int> local_to_cloud_trajectory_id_map_;
|
std::map<int, int> local_to_cloud_trajectory_id_map_;
|
||||||
cartographer::common::BlockingQueue<
|
common::BlockingQueue<std::unique_ptr<google::protobuf::Message>> send_queue_;
|
||||||
std::unique_ptr<google::protobuf::Message>>
|
|
||||||
send_queue_;
|
|
||||||
bool shutting_down_ = false;
|
bool shutting_down_ = false;
|
||||||
std::unique_ptr<std::thread> upload_thread_;
|
std::unique_ptr<std::thread> upload_thread_;
|
||||||
std::unique_ptr<framework::Client<handlers::AddFixedFramePoseDataHandler>>
|
std::unique_ptr<framework::Client<handlers::AddFixedFramePoseDataHandler>>
|
||||||
|
@ -227,7 +224,7 @@ void LocalTrajectoryUploader::ProcessLocalSlamResultDataMessage(
|
||||||
TranslateTrajectoryId(data_request->mutable_sensor_metadata());
|
TranslateTrajectoryId(data_request->mutable_sensor_metadata());
|
||||||
// A submap also holds a trajectory id that must be translated to uplink's
|
// A submap also holds a trajectory id that must be translated to uplink's
|
||||||
// trajectory id.
|
// trajectory id.
|
||||||
for (cartographer::mapping::proto::Submap &mutable_submap :
|
for (mapping::proto::Submap &mutable_submap :
|
||||||
*data_request->mutable_local_slam_result_data()->mutable_submaps()) {
|
*data_request->mutable_local_slam_result_data()->mutable_submaps()) {
|
||||||
mutable_submap.mutable_submap_id()->set_trajectory_id(
|
mutable_submap.mutable_submap_id()->set_trajectory_id(
|
||||||
data_request->sensor_metadata().trajectory_id());
|
data_request->sensor_metadata().trajectory_id());
|
||||||
|
@ -237,18 +234,17 @@ void LocalTrajectoryUploader::ProcessLocalSlamResultDataMessage(
|
||||||
|
|
||||||
void LocalTrajectoryUploader::AddTrajectory(
|
void LocalTrajectoryUploader::AddTrajectory(
|
||||||
int local_trajectory_id, const std::set<SensorId> &expected_sensor_ids,
|
int local_trajectory_id, const std::set<SensorId> &expected_sensor_ids,
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptions
|
const mapping::proto::TrajectoryBuilderOptions &trajectory_options) {
|
||||||
&trajectory_options) {
|
|
||||||
proto::AddTrajectoryRequest request;
|
proto::AddTrajectoryRequest request;
|
||||||
*request.mutable_trajectory_builder_options() = trajectory_options;
|
*request.mutable_trajectory_builder_options() = trajectory_options;
|
||||||
for (const SensorId &sensor_id : expected_sensor_ids) {
|
for (const SensorId &sensor_id : expected_sensor_ids) {
|
||||||
// Range sensors are not forwarded, but combined into a LocalSlamResult.
|
// Range sensors are not forwarded, but combined into a LocalSlamResult.
|
||||||
if (sensor_id.type != SensorId::SensorType::RANGE) {
|
if (sensor_id.type != SensorId::SensorType::RANGE) {
|
||||||
*request.add_expected_sensor_ids() = sensor::ToProto(sensor_id);
|
*request.add_expected_sensor_ids() = cloud::ToProto(sensor_id);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
*request.add_expected_sensor_ids() =
|
*request.add_expected_sensor_ids() =
|
||||||
sensor::ToProto(GetLocalSlamResultSensorId(local_trajectory_id));
|
cloud::ToProto(GetLocalSlamResultSensorId(local_trajectory_id));
|
||||||
framework::Client<handlers::AddTrajectoryHandler> client(client_channel_);
|
framework::Client<handlers::AddTrajectoryHandler> client(client_channel_);
|
||||||
CHECK(client.Write(request));
|
CHECK(client.Write(request));
|
||||||
CHECK_EQ(local_to_cloud_trajectory_id_map_.count(local_trajectory_id), 0);
|
CHECK_EQ(local_to_cloud_trajectory_id_map_.count(local_trajectory_id), 0);
|
||||||
|
@ -278,4 +274,5 @@ std::unique_ptr<LocalTrajectoryUploaderInterface> CreateLocalTrajectoryUploader(
|
||||||
return make_unique<LocalTrajectoryUploader>(uplink_server_address);
|
return make_unique<LocalTrajectoryUploader>(uplink_server_address);
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -24,11 +24,12 @@
|
||||||
#include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
|
#include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
|
||||||
#include "cartographer/mapping/trajectory_builder_interface.h"
|
#include "cartographer/mapping/trajectory_builder_interface.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
class LocalTrajectoryUploaderInterface {
|
class LocalTrajectoryUploaderInterface {
|
||||||
public:
|
public:
|
||||||
using SensorId = cartographer::mapping::TrajectoryBuilderInterface::SensorId;
|
using SensorId = mapping::TrajectoryBuilderInterface::SensorId;
|
||||||
|
|
||||||
virtual ~LocalTrajectoryUploaderInterface() = default;
|
virtual ~LocalTrajectoryUploaderInterface() = default;
|
||||||
|
|
||||||
|
@ -44,8 +45,7 @@ class LocalTrajectoryUploaderInterface {
|
||||||
std::unique_ptr<google::protobuf::Message> data_request) = 0;
|
std::unique_ptr<google::protobuf::Message> data_request) = 0;
|
||||||
virtual void AddTrajectory(
|
virtual void AddTrajectory(
|
||||||
int local_trajectory_id, const std::set<SensorId>& expected_sensor_ids,
|
int local_trajectory_id, const std::set<SensorId>& expected_sensor_ids,
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptions&
|
const mapping::proto::TrajectoryBuilderOptions& trajectory_options) = 0;
|
||||||
trajectory_options) = 0;
|
|
||||||
virtual void FinishTrajectory(int local_trajectory_id) = 0;
|
virtual void FinishTrajectory(int local_trajectory_id) = 0;
|
||||||
|
|
||||||
virtual SensorId GetLocalSlamResultSensorId(
|
virtual SensorId GetLocalSlamResultSensorId(
|
||||||
|
@ -56,6 +56,7 @@ class LocalTrajectoryUploaderInterface {
|
||||||
std::unique_ptr<LocalTrajectoryUploaderInterface> CreateLocalTrajectoryUploader(
|
std::unique_ptr<LocalTrajectoryUploaderInterface> CreateLocalTrajectoryUploader(
|
||||||
const std::string& uplink_server_address);
|
const std::string& uplink_server_address);
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_LOCAL_TRAJECTORY_UPLOADER_H
|
#endif // CARTOGRAPHER_GRPC_LOCAL_TRAJECTORY_UPLOADER_H
|
||||||
|
|
|
@ -18,30 +18,29 @@
|
||||||
|
|
||||||
#include "cartographer_grpc/internal/map_builder_server.h"
|
#include "cartographer_grpc/internal/map_builder_server.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
MapBuilderContext::MapBuilderContext(MapBuilderServer* map_builder_server)
|
MapBuilderContext::MapBuilderContext(MapBuilderServer* map_builder_server)
|
||||||
: map_builder_server_(map_builder_server) {}
|
: map_builder_server_(map_builder_server) {}
|
||||||
|
|
||||||
cartographer::mapping::MapBuilderInterface& MapBuilderContext::map_builder() {
|
mapping::MapBuilderInterface& MapBuilderContext::map_builder() {
|
||||||
return *map_builder_server_->map_builder_;
|
return *map_builder_server_->map_builder_;
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::common::BlockingQueue<
|
common::BlockingQueue<std::unique_ptr<MapBuilderContextInterface::Data>>&
|
||||||
std::unique_ptr<MapBuilderContextInterface::Data>>&
|
|
||||||
MapBuilderContext::sensor_data_queue() {
|
MapBuilderContext::sensor_data_queue() {
|
||||||
return map_builder_server_->incoming_data_queue_;
|
return map_builder_server_->incoming_data_queue_;
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::TrajectoryBuilderInterface::LocalSlamResultCallback
|
mapping::TrajectoryBuilderInterface::LocalSlamResultCallback
|
||||||
MapBuilderContext::GetLocalSlamResultCallbackForSubscriptions() {
|
MapBuilderContext::GetLocalSlamResultCallbackForSubscriptions() {
|
||||||
MapBuilderServer* map_builder_server = map_builder_server_;
|
MapBuilderServer* map_builder_server = map_builder_server_;
|
||||||
return [map_builder_server](
|
return [map_builder_server](
|
||||||
int trajectory_id, cartographer::common::Time time,
|
int trajectory_id, common::Time time,
|
||||||
cartographer::transform::Rigid3d local_pose,
|
transform::Rigid3d local_pose, sensor::RangeData range_data,
|
||||||
cartographer::sensor::RangeData range_data,
|
std::unique_ptr<
|
||||||
std::unique_ptr<const cartographer::mapping::
|
const mapping::TrajectoryBuilderInterface::InsertionResult>
|
||||||
TrajectoryBuilderInterface::InsertionResult>
|
|
||||||
insertion_result) {
|
insertion_result) {
|
||||||
map_builder_server->OnLocalSlamResult(trajectory_id, time, local_pose,
|
map_builder_server->OnLocalSlamResult(trajectory_id, time, local_pose,
|
||||||
std::move(range_data),
|
std::move(range_data),
|
||||||
|
@ -71,23 +70,21 @@ void MapBuilderContext::NotifyFinishTrajectory(int trajectory_id) {
|
||||||
map_builder_server_->NotifyFinishTrajectory(trajectory_id);
|
map_builder_server_->NotifyFinishTrajectory(trajectory_id);
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_ptr<cartographer::mapping::Submap2D>
|
std::shared_ptr<mapping::Submap2D> MapBuilderContext::UpdateSubmap2D(
|
||||||
MapBuilderContext::UpdateSubmap2D(
|
const mapping::proto::Submap& proto) {
|
||||||
const cartographer::mapping::proto::Submap& proto) {
|
|
||||||
CHECK(proto.has_submap_2d());
|
CHECK(proto.has_submap_2d());
|
||||||
cartographer::mapping::SubmapId submap_id{proto.submap_id().trajectory_id(),
|
mapping::SubmapId submap_id{proto.submap_id().trajectory_id(),
|
||||||
proto.submap_id().submap_index()};
|
proto.submap_id().submap_index()};
|
||||||
std::shared_ptr<cartographer::mapping::Submap2D> submap_2d_ptr;
|
std::shared_ptr<mapping::Submap2D> submap_2d_ptr;
|
||||||
auto submap_it = unfinished_submaps_.find(submap_id);
|
auto submap_it = unfinished_submaps_.find(submap_id);
|
||||||
if (submap_it == unfinished_submaps_.end()) {
|
if (submap_it == unfinished_submaps_.end()) {
|
||||||
// Seeing a submap for the first time it should never be finished.
|
// Seeing a submap for the first time it should never be finished.
|
||||||
CHECK(!proto.submap_2d().finished());
|
CHECK(!proto.submap_2d().finished());
|
||||||
submap_2d_ptr =
|
submap_2d_ptr = std::make_shared<mapping::Submap2D>(proto.submap_2d());
|
||||||
std::make_shared<cartographer::mapping::Submap2D>(proto.submap_2d());
|
|
||||||
unfinished_submaps_.Insert(submap_id, submap_2d_ptr);
|
unfinished_submaps_.Insert(submap_id, submap_2d_ptr);
|
||||||
} else {
|
} else {
|
||||||
submap_2d_ptr = std::dynamic_pointer_cast<cartographer::mapping::Submap2D>(
|
submap_2d_ptr =
|
||||||
submap_it->data);
|
std::dynamic_pointer_cast<mapping::Submap2D>(submap_it->data);
|
||||||
CHECK(submap_2d_ptr);
|
CHECK(submap_2d_ptr);
|
||||||
submap_2d_ptr->UpdateFromProto(proto);
|
submap_2d_ptr->UpdateFromProto(proto);
|
||||||
|
|
||||||
|
@ -104,24 +101,22 @@ MapBuilderContext::UpdateSubmap2D(
|
||||||
return submap_2d_ptr;
|
return submap_2d_ptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::shared_ptr<cartographer::mapping::Submap3D>
|
std::shared_ptr<mapping::Submap3D> MapBuilderContext::UpdateSubmap3D(
|
||||||
MapBuilderContext::UpdateSubmap3D(
|
const mapping::proto::Submap& proto) {
|
||||||
const cartographer::mapping::proto::Submap& proto) {
|
|
||||||
CHECK(proto.has_submap_3d());
|
CHECK(proto.has_submap_3d());
|
||||||
cartographer::mapping::SubmapId submap_id{proto.submap_id().trajectory_id(),
|
mapping::SubmapId submap_id{proto.submap_id().trajectory_id(),
|
||||||
proto.submap_id().submap_index()};
|
proto.submap_id().submap_index()};
|
||||||
std::shared_ptr<cartographer::mapping::Submap3D> submap_3d_ptr;
|
std::shared_ptr<mapping::Submap3D> submap_3d_ptr;
|
||||||
auto submap_it = unfinished_submaps_.find(submap_id);
|
auto submap_it = unfinished_submaps_.find(submap_id);
|
||||||
if (submap_it == unfinished_submaps_.end()) {
|
if (submap_it == unfinished_submaps_.end()) {
|
||||||
// Seeing a submap for the first time it should never be finished.
|
// Seeing a submap for the first time it should never be finished.
|
||||||
CHECK(!proto.submap_3d().finished());
|
CHECK(!proto.submap_3d().finished());
|
||||||
submap_3d_ptr =
|
submap_3d_ptr = std::make_shared<mapping::Submap3D>(proto.submap_3d());
|
||||||
std::make_shared<cartographer::mapping::Submap3D>(proto.submap_3d());
|
|
||||||
unfinished_submaps_.Insert(submap_id, submap_3d_ptr);
|
unfinished_submaps_.Insert(submap_id, submap_3d_ptr);
|
||||||
submap_it = unfinished_submaps_.find(submap_id);
|
submap_it = unfinished_submaps_.find(submap_id);
|
||||||
} else {
|
} else {
|
||||||
submap_3d_ptr = std::dynamic_pointer_cast<cartographer::mapping::Submap3D>(
|
submap_3d_ptr =
|
||||||
submap_it->data);
|
std::dynamic_pointer_cast<mapping::Submap3D>(submap_it->data);
|
||||||
CHECK(submap_3d_ptr);
|
CHECK(submap_3d_ptr);
|
||||||
|
|
||||||
// Update submap with information in incoming request.
|
// Update submap with information in incoming request.
|
||||||
|
@ -140,33 +135,31 @@ MapBuilderContext::UpdateSubmap3D(
|
||||||
return submap_3d_ptr;
|
return submap_3d_ptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
std::unique_ptr<mapping::LocalSlamResultData>
|
||||||
MapBuilderContext::ProcessLocalSlamResultData(
|
MapBuilderContext::ProcessLocalSlamResultData(
|
||||||
const std::string& sensor_id, cartographer::common::Time time,
|
const std::string& sensor_id, common::Time time,
|
||||||
const cartographer::mapping::proto::LocalSlamResultData& proto) {
|
const mapping::proto::LocalSlamResultData& proto) {
|
||||||
CHECK_GE(proto.submaps().size(), 1);
|
CHECK_GE(proto.submaps().size(), 1);
|
||||||
CHECK(proto.submaps(0).has_submap_2d() || proto.submaps(0).has_submap_3d());
|
CHECK(proto.submaps(0).has_submap_2d() || proto.submaps(0).has_submap_3d());
|
||||||
if (proto.submaps(0).has_submap_2d()) {
|
if (proto.submaps(0).has_submap_2d()) {
|
||||||
std::vector<std::shared_ptr<const cartographer::mapping::Submap2D>> submaps;
|
std::vector<std::shared_ptr<const mapping::Submap2D>> submaps;
|
||||||
for (const auto& submap_proto : proto.submaps()) {
|
for (const auto& submap_proto : proto.submaps()) {
|
||||||
submaps.push_back(UpdateSubmap2D(submap_proto));
|
submaps.push_back(UpdateSubmap2D(submap_proto));
|
||||||
}
|
}
|
||||||
return cartographer::common::make_unique<
|
return common::make_unique<mapping::LocalSlamResult2D>(
|
||||||
cartographer::mapping::LocalSlamResult2D>(
|
|
||||||
sensor_id, time,
|
sensor_id, time,
|
||||||
std::make_shared<const cartographer::mapping::TrajectoryNode::Data>(
|
std::make_shared<const mapping::TrajectoryNode::Data>(
|
||||||
cartographer::mapping::FromProto(proto.node_data())),
|
mapping::FromProto(proto.node_data())),
|
||||||
submaps);
|
submaps);
|
||||||
} else {
|
} else {
|
||||||
std::vector<std::shared_ptr<const cartographer::mapping::Submap3D>> submaps;
|
std::vector<std::shared_ptr<const mapping::Submap3D>> submaps;
|
||||||
for (const auto& submap_proto : proto.submaps()) {
|
for (const auto& submap_proto : proto.submaps()) {
|
||||||
submaps.push_back(UpdateSubmap3D(submap_proto));
|
submaps.push_back(UpdateSubmap3D(submap_proto));
|
||||||
}
|
}
|
||||||
return cartographer::common::make_unique<
|
return common::make_unique<mapping::LocalSlamResult3D>(
|
||||||
cartographer::mapping::LocalSlamResult3D>(
|
|
||||||
sensor_id, time,
|
sensor_id, time,
|
||||||
std::make_shared<const cartographer::mapping::TrajectoryNode::Data>(
|
std::make_shared<const mapping::TrajectoryNode::Data>(
|
||||||
cartographer::mapping::FromProto(proto.node_data())),
|
mapping::FromProto(proto.node_data())),
|
||||||
std::move(submaps));
|
std::move(submaps));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -176,20 +169,18 @@ MapBuilderContext::local_trajectory_uploader() {
|
||||||
return map_builder_server_->local_trajectory_uploader_.get();
|
return map_builder_server_->local_trajectory_uploader_.get();
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilderContext::EnqueueSensorData(
|
void MapBuilderContext::EnqueueSensorData(int trajectory_id,
|
||||||
int trajectory_id, std::unique_ptr<cartographer::sensor::Data> data) {
|
std::unique_ptr<sensor::Data> data) {
|
||||||
map_builder_server_->incoming_data_queue_.Push(
|
map_builder_server_->incoming_data_queue_.Push(
|
||||||
cartographer::common::make_unique<Data>(
|
common::make_unique<Data>(Data{trajectory_id, std::move(data)}));
|
||||||
Data{trajectory_id, std::move(data)}));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilderContext::EnqueueLocalSlamResultData(
|
void MapBuilderContext::EnqueueLocalSlamResultData(
|
||||||
int trajectory_id, const std::string& sensor_id,
|
int trajectory_id, const std::string& sensor_id,
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
std::unique_ptr<mapping::LocalSlamResultData> local_slam_result_data) {
|
||||||
local_slam_result_data) {
|
map_builder_server_->incoming_data_queue_.Push(common::make_unique<Data>(
|
||||||
map_builder_server_->incoming_data_queue_.Push(
|
Data{trajectory_id, std::move(local_slam_result_data)}));
|
||||||
cartographer::common::make_unique<Data>(
|
|
||||||
Data{trajectory_id, std::move(local_slam_result_data)}));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,15 +21,15 @@
|
||||||
#include "cartographer/mapping/3d/submap_3d.h"
|
#include "cartographer/mapping/3d/submap_3d.h"
|
||||||
#include "cartographer_grpc/internal/map_builder_context_interface.h"
|
#include "cartographer_grpc/internal/map_builder_context_interface.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
class MapBuilderContext : public MapBuilderContextInterface {
|
class MapBuilderContext : public MapBuilderContextInterface {
|
||||||
public:
|
public:
|
||||||
MapBuilderContext(MapBuilderServer* map_builder_server);
|
MapBuilderContext(MapBuilderServer* map_builder_server);
|
||||||
cartographer::mapping::MapBuilderInterface& map_builder() override;
|
mapping::MapBuilderInterface& map_builder() override;
|
||||||
cartographer::common::BlockingQueue<std::unique_ptr<Data>>&
|
common::BlockingQueue<std::unique_ptr<Data>>& sensor_data_queue() override;
|
||||||
sensor_data_queue() override;
|
mapping::TrajectoryBuilderInterface::LocalSlamResultCallback
|
||||||
cartographer::mapping::TrajectoryBuilderInterface::LocalSlamResultCallback
|
|
||||||
GetLocalSlamResultCallbackForSubscriptions() override;
|
GetLocalSlamResultCallbackForSubscriptions() override;
|
||||||
void AddSensorDataToTrajectory(const Data& sensor_data) override;
|
void AddSensorDataToTrajectory(const Data& sensor_data) override;
|
||||||
SubscriptionId SubscribeLocalSlamResults(
|
SubscriptionId SubscribeLocalSlamResults(
|
||||||
|
@ -37,31 +37,29 @@ class MapBuilderContext : public MapBuilderContextInterface {
|
||||||
void UnsubscribeLocalSlamResults(
|
void UnsubscribeLocalSlamResults(
|
||||||
const SubscriptionId& subscription_id) override;
|
const SubscriptionId& subscription_id) override;
|
||||||
void NotifyFinishTrajectory(int trajectory_id) override;
|
void NotifyFinishTrajectory(int trajectory_id) override;
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
std::unique_ptr<mapping::LocalSlamResultData> ProcessLocalSlamResultData(
|
||||||
ProcessLocalSlamResultData(
|
const std::string& sensor_id, common::Time time,
|
||||||
const std::string& sensor_id, cartographer::common::Time time,
|
const mapping::proto::LocalSlamResultData& proto) override;
|
||||||
const cartographer::mapping::proto::LocalSlamResultData& proto) override;
|
|
||||||
LocalTrajectoryUploaderInterface* local_trajectory_uploader() override;
|
LocalTrajectoryUploaderInterface* local_trajectory_uploader() override;
|
||||||
void EnqueueSensorData(
|
void EnqueueSensorData(int trajectory_id,
|
||||||
int trajectory_id,
|
std::unique_ptr<sensor::Data> data) override;
|
||||||
std::unique_ptr<cartographer::sensor::Data> data) override;
|
void EnqueueLocalSlamResultData(int trajectory_id,
|
||||||
void EnqueueLocalSlamResultData(
|
const std::string& sensor_id,
|
||||||
int trajectory_id, const std::string& sensor_id,
|
std::unique_ptr<mapping::LocalSlamResultData>
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
local_slam_result_data) override;
|
||||||
local_slam_result_data) override;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
std::shared_ptr<cartographer::mapping::Submap2D> UpdateSubmap2D(
|
std::shared_ptr<mapping::Submap2D> UpdateSubmap2D(
|
||||||
const cartographer::mapping::proto::Submap& proto);
|
const mapping::proto::Submap& proto);
|
||||||
std::shared_ptr<cartographer::mapping::Submap3D> UpdateSubmap3D(
|
std::shared_ptr<mapping::Submap3D> UpdateSubmap3D(
|
||||||
const cartographer::mapping::proto::Submap& proto);
|
const mapping::proto::Submap& proto);
|
||||||
|
|
||||||
MapBuilderServer* map_builder_server_;
|
MapBuilderServer* map_builder_server_;
|
||||||
cartographer::mapping::MapById<cartographer::mapping::SubmapId,
|
mapping::MapById<mapping::SubmapId, std::shared_ptr<mapping::Submap>>
|
||||||
std::shared_ptr<cartographer::mapping::Submap>>
|
|
||||||
unfinished_submaps_;
|
unfinished_submaps_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_CONTEXT_H
|
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_CONTEXT_H
|
||||||
|
|
|
@ -25,18 +25,18 @@
|
||||||
#include "cartographer_grpc/internal/framework/execution_context.h"
|
#include "cartographer_grpc/internal/framework/execution_context.h"
|
||||||
#include "cartographer_grpc/internal/local_trajectory_uploader.h"
|
#include "cartographer_grpc/internal/local_trajectory_uploader.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
class MapBuilderServer;
|
class MapBuilderServer;
|
||||||
class MapBuilderContextInterface : public framework::ExecutionContext {
|
class MapBuilderContextInterface : public framework::ExecutionContext {
|
||||||
public:
|
public:
|
||||||
struct LocalSlamResult {
|
struct LocalSlamResult {
|
||||||
int trajectory_id;
|
int trajectory_id;
|
||||||
cartographer::common::Time time;
|
common::Time time;
|
||||||
cartographer::transform::Rigid3d local_pose;
|
transform::Rigid3d local_pose;
|
||||||
std::shared_ptr<const cartographer::sensor::RangeData> range_data;
|
std::shared_ptr<const sensor::RangeData> range_data;
|
||||||
std::unique_ptr<const cartographer::mapping::TrajectoryBuilderInterface::
|
std::unique_ptr<const mapping::TrajectoryBuilderInterface::InsertionResult>
|
||||||
InsertionResult>
|
|
||||||
insertion_result;
|
insertion_result;
|
||||||
};
|
};
|
||||||
// Calling with 'nullptr' signals subscribers that the subscription has ended.
|
// Calling with 'nullptr' signals subscribers that the subscription has ended.
|
||||||
|
@ -44,7 +44,7 @@ class MapBuilderContextInterface : public framework::ExecutionContext {
|
||||||
std::function<void(std::unique_ptr<LocalSlamResult>)>;
|
std::function<void(std::unique_ptr<LocalSlamResult>)>;
|
||||||
struct Data {
|
struct Data {
|
||||||
int trajectory_id;
|
int trajectory_id;
|
||||||
std::unique_ptr<cartographer::sensor::Data> data;
|
std::unique_ptr<sensor::Data> data;
|
||||||
};
|
};
|
||||||
struct SubscriptionId {
|
struct SubscriptionId {
|
||||||
const int trajectory_id;
|
const int trajectory_id;
|
||||||
|
@ -58,31 +58,29 @@ class MapBuilderContextInterface : public framework::ExecutionContext {
|
||||||
MapBuilderContextInterface& operator=(const MapBuilderContextInterface&) =
|
MapBuilderContextInterface& operator=(const MapBuilderContextInterface&) =
|
||||||
delete;
|
delete;
|
||||||
|
|
||||||
virtual cartographer::mapping::MapBuilderInterface& map_builder() = 0;
|
virtual mapping::MapBuilderInterface& map_builder() = 0;
|
||||||
virtual cartographer::common::BlockingQueue<std::unique_ptr<Data>>&
|
virtual common::BlockingQueue<std::unique_ptr<Data>>& sensor_data_queue() = 0;
|
||||||
sensor_data_queue() = 0;
|
virtual mapping::TrajectoryBuilderInterface::LocalSlamResultCallback
|
||||||
virtual cartographer::mapping::TrajectoryBuilderInterface::
|
GetLocalSlamResultCallbackForSubscriptions() = 0;
|
||||||
LocalSlamResultCallback
|
|
||||||
GetLocalSlamResultCallbackForSubscriptions() = 0;
|
|
||||||
virtual void AddSensorDataToTrajectory(const Data& sensor_data) = 0;
|
virtual void AddSensorDataToTrajectory(const Data& sensor_data) = 0;
|
||||||
virtual SubscriptionId SubscribeLocalSlamResults(
|
virtual SubscriptionId SubscribeLocalSlamResults(
|
||||||
int trajectory_id, LocalSlamSubscriptionCallback callback) = 0;
|
int trajectory_id, LocalSlamSubscriptionCallback callback) = 0;
|
||||||
virtual void UnsubscribeLocalSlamResults(
|
virtual void UnsubscribeLocalSlamResults(
|
||||||
const SubscriptionId& subscription_id) = 0;
|
const SubscriptionId& subscription_id) = 0;
|
||||||
virtual void NotifyFinishTrajectory(int trajectory_id) = 0;
|
virtual void NotifyFinishTrajectory(int trajectory_id) = 0;
|
||||||
virtual std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
virtual std::unique_ptr<mapping::LocalSlamResultData>
|
||||||
ProcessLocalSlamResultData(
|
ProcessLocalSlamResultData(
|
||||||
const std::string& sensor_id, cartographer::common::Time time,
|
const std::string& sensor_id, common::Time time,
|
||||||
const cartographer::mapping::proto::LocalSlamResultData& proto) = 0;
|
const mapping::proto::LocalSlamResultData& proto) = 0;
|
||||||
virtual LocalTrajectoryUploaderInterface* local_trajectory_uploader() = 0;
|
virtual LocalTrajectoryUploaderInterface* local_trajectory_uploader() = 0;
|
||||||
virtual void EnqueueSensorData(
|
virtual void EnqueueSensorData(int trajectory_id,
|
||||||
int trajectory_id, std::unique_ptr<cartographer::sensor::Data> data) = 0;
|
std::unique_ptr<sensor::Data> data) = 0;
|
||||||
virtual void EnqueueLocalSlamResultData(
|
virtual void EnqueueLocalSlamResultData(
|
||||||
int trajectory_id, const std::string& sensor_id,
|
int trajectory_id, const std::string& sensor_id,
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
std::unique_ptr<mapping::LocalSlamResultData> local_slam_result_data) = 0;
|
||||||
local_slam_result_data) = 0;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_CONTEXT_INTERFACE_H
|
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_CONTEXT_INTERFACE_H
|
||||||
|
|
|
@ -37,17 +37,17 @@
|
||||||
#include "cartographer_grpc/internal/sensor/serialization.h"
|
#include "cartographer_grpc/internal/sensor/serialization.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
const cartographer::common::Duration kPopTimeout =
|
const common::Duration kPopTimeout = common::FromMilliseconds(100);
|
||||||
cartographer::common::FromMilliseconds(100);
|
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
|
|
||||||
MapBuilderServer::MapBuilderServer(
|
MapBuilderServer::MapBuilderServer(
|
||||||
const proto::MapBuilderServerOptions& map_builder_server_options,
|
const proto::MapBuilderServerOptions& map_builder_server_options,
|
||||||
std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder)
|
std::unique_ptr<mapping::MapBuilderInterface> map_builder)
|
||||||
: map_builder_(std::move(map_builder)) {
|
: map_builder_(std::move(map_builder)) {
|
||||||
framework::Server::Builder server_builder;
|
framework::Server::Builder server_builder;
|
||||||
server_builder.SetServerAddress(map_builder_server_options.server_address());
|
server_builder.SetServerAddress(map_builder_server_options.server_address());
|
||||||
|
@ -79,7 +79,7 @@ MapBuilderServer::MapBuilderServer(
|
||||||
server_builder.RegisterHandler<handlers::WriteStateHandler>();
|
server_builder.RegisterHandler<handlers::WriteStateHandler>();
|
||||||
grpc_server_ = server_builder.Build();
|
grpc_server_ = server_builder.Build();
|
||||||
grpc_server_->SetExecutionContext(
|
grpc_server_->SetExecutionContext(
|
||||||
cartographer::common::make_unique<MapBuilderContext>(this));
|
common::make_unique<MapBuilderContext>(this));
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilderServer::Start() {
|
void MapBuilderServer::Start() {
|
||||||
|
@ -125,33 +125,31 @@ void MapBuilderServer::StartSlamThread() {
|
||||||
CHECK(!slam_thread_);
|
CHECK(!slam_thread_);
|
||||||
|
|
||||||
// Start the SLAM processing thread.
|
// Start the SLAM processing thread.
|
||||||
slam_thread_ = cartographer::common::make_unique<std::thread>(
|
slam_thread_ = common::make_unique<std::thread>(
|
||||||
[this]() { this->ProcessSensorDataQueue(); });
|
[this]() { this->ProcessSensorDataQueue(); });
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilderServer::OnLocalSlamResult(
|
void MapBuilderServer::OnLocalSlamResult(
|
||||||
int trajectory_id, cartographer::common::Time time,
|
int trajectory_id, common::Time time, transform::Rigid3d local_pose,
|
||||||
cartographer::transform::Rigid3d local_pose,
|
sensor::RangeData range_data,
|
||||||
cartographer::sensor::RangeData range_data,
|
std::unique_ptr<const mapping::TrajectoryBuilderInterface::InsertionResult>
|
||||||
std::unique_ptr<const cartographer::mapping::TrajectoryBuilderInterface::
|
|
||||||
InsertionResult>
|
|
||||||
insertion_result) {
|
insertion_result) {
|
||||||
auto shared_range_data =
|
auto shared_range_data =
|
||||||
std::make_shared<cartographer::sensor::RangeData>(std::move(range_data));
|
std::make_shared<sensor::RangeData>(std::move(range_data));
|
||||||
|
|
||||||
// If there is an uplink server and a submap insertion happened, enqueue this
|
// If there is an uplink server and a submap insertion happened, enqueue this
|
||||||
// local SLAM result for uploading.
|
// local SLAM result for uploading.
|
||||||
if (insertion_result &&
|
if (insertion_result &&
|
||||||
grpc_server_->GetUnsynchronizedContext<MapBuilderContext>()
|
grpc_server_->GetUnsynchronizedContext<MapBuilderContext>()
|
||||||
->local_trajectory_uploader()) {
|
->local_trajectory_uploader()) {
|
||||||
auto data_request = cartographer::common::make_unique<
|
auto data_request =
|
||||||
proto::AddLocalSlamResultDataRequest>();
|
common::make_unique<proto::AddLocalSlamResultDataRequest>();
|
||||||
auto sensor_id = grpc_server_->GetUnsynchronizedContext<MapBuilderContext>()
|
auto sensor_id = grpc_server_->GetUnsynchronizedContext<MapBuilderContext>()
|
||||||
->local_trajectory_uploader()
|
->local_trajectory_uploader()
|
||||||
->GetLocalSlamResultSensorId(trajectory_id);
|
->GetLocalSlamResultSensorId(trajectory_id);
|
||||||
sensor::CreateAddLocalSlamResultDataRequest(
|
CreateAddLocalSlamResultDataRequest(sensor_id.id, trajectory_id, time,
|
||||||
sensor_id.id, trajectory_id, time, starting_submap_index_,
|
starting_submap_index_,
|
||||||
*insertion_result, data_request.get());
|
*insertion_result, data_request.get());
|
||||||
// TODO(cschuet): Make this more robust.
|
// TODO(cschuet): Make this more robust.
|
||||||
if (insertion_result->insertion_submaps.front()->finished()) {
|
if (insertion_result->insertion_submaps.front()->finished()) {
|
||||||
++starting_submap_index_;
|
++starting_submap_index_;
|
||||||
|
@ -161,18 +159,17 @@ void MapBuilderServer::OnLocalSlamResult(
|
||||||
->EnqueueDataRequest(std::move(data_request));
|
->EnqueueDataRequest(std::move(data_request));
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::common::MutexLocker locker(&local_slam_subscriptions_lock_);
|
common::MutexLocker locker(&local_slam_subscriptions_lock_);
|
||||||
for (auto& entry : local_slam_subscriptions_[trajectory_id]) {
|
for (auto& entry : local_slam_subscriptions_[trajectory_id]) {
|
||||||
auto copy_of_insertion_result =
|
auto copy_of_insertion_result =
|
||||||
insertion_result
|
insertion_result
|
||||||
? cartographer::common::make_unique<
|
? common::make_unique<
|
||||||
const cartographer::mapping::TrajectoryBuilderInterface::
|
const mapping::TrajectoryBuilderInterface::InsertionResult>(
|
||||||
InsertionResult>(*insertion_result)
|
*insertion_result)
|
||||||
: nullptr;
|
: nullptr;
|
||||||
MapBuilderContextInterface::LocalSlamSubscriptionCallback callback =
|
MapBuilderContextInterface::LocalSlamSubscriptionCallback callback =
|
||||||
entry.second;
|
entry.second;
|
||||||
callback(cartographer::common::make_unique<
|
callback(common::make_unique<MapBuilderContextInterface::LocalSlamResult>(
|
||||||
MapBuilderContextInterface::LocalSlamResult>(
|
|
||||||
MapBuilderContextInterface::LocalSlamResult{
|
MapBuilderContextInterface::LocalSlamResult{
|
||||||
trajectory_id, time, local_pose, shared_range_data,
|
trajectory_id, time, local_pose, shared_range_data,
|
||||||
std::move(copy_of_insertion_result)}));
|
std::move(copy_of_insertion_result)}));
|
||||||
|
@ -183,7 +180,7 @@ MapBuilderContextInterface::SubscriptionId
|
||||||
MapBuilderServer::SubscribeLocalSlamResults(
|
MapBuilderServer::SubscribeLocalSlamResults(
|
||||||
int trajectory_id,
|
int trajectory_id,
|
||||||
MapBuilderContextInterface::LocalSlamSubscriptionCallback callback) {
|
MapBuilderContextInterface::LocalSlamSubscriptionCallback callback) {
|
||||||
cartographer::common::MutexLocker locker(&local_slam_subscriptions_lock_);
|
common::MutexLocker locker(&local_slam_subscriptions_lock_);
|
||||||
local_slam_subscriptions_[trajectory_id].emplace(current_subscription_index_,
|
local_slam_subscriptions_[trajectory_id].emplace(current_subscription_index_,
|
||||||
callback);
|
callback);
|
||||||
return MapBuilderContextInterface::SubscriptionId{
|
return MapBuilderContextInterface::SubscriptionId{
|
||||||
|
@ -192,14 +189,14 @@ MapBuilderServer::SubscribeLocalSlamResults(
|
||||||
|
|
||||||
void MapBuilderServer::UnsubscribeLocalSlamResults(
|
void MapBuilderServer::UnsubscribeLocalSlamResults(
|
||||||
const MapBuilderContextInterface::SubscriptionId& subscription_id) {
|
const MapBuilderContextInterface::SubscriptionId& subscription_id) {
|
||||||
cartographer::common::MutexLocker locker(&local_slam_subscriptions_lock_);
|
common::MutexLocker locker(&local_slam_subscriptions_lock_);
|
||||||
CHECK_EQ(local_slam_subscriptions_[subscription_id.trajectory_id].erase(
|
CHECK_EQ(local_slam_subscriptions_[subscription_id.trajectory_id].erase(
|
||||||
subscription_id.subscription_index),
|
subscription_id.subscription_index),
|
||||||
1u);
|
1u);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MapBuilderServer::NotifyFinishTrajectory(int trajectory_id) {
|
void MapBuilderServer::NotifyFinishTrajectory(int trajectory_id) {
|
||||||
cartographer::common::MutexLocker locker(&local_slam_subscriptions_lock_);
|
common::MutexLocker locker(&local_slam_subscriptions_lock_);
|
||||||
for (auto& entry : local_slam_subscriptions_[trajectory_id]) {
|
for (auto& entry : local_slam_subscriptions_[trajectory_id]) {
|
||||||
MapBuilderContextInterface::LocalSlamSubscriptionCallback callback =
|
MapBuilderContextInterface::LocalSlamSubscriptionCallback callback =
|
||||||
entry.second;
|
entry.second;
|
||||||
|
@ -213,4 +210,5 @@ void MapBuilderServer::WaitUntilIdle() {
|
||||||
map_builder_->pose_graph()->RunFinalOptimization();
|
map_builder_->pose_graph()->RunFinalOptimization();
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -30,7 +30,8 @@
|
||||||
#include "cartographer_grpc/map_builder_server_interface.h"
|
#include "cartographer_grpc/map_builder_server_interface.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_server_options.pb.h"
|
#include "cartographer_grpc/proto/map_builder_server_options.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
class MapBuilderServer : public MapBuilderServerInterface {
|
class MapBuilderServer : public MapBuilderServerInterface {
|
||||||
public:
|
public:
|
||||||
|
@ -38,7 +39,7 @@ class MapBuilderServer : public MapBuilderServerInterface {
|
||||||
|
|
||||||
MapBuilderServer(
|
MapBuilderServer(
|
||||||
const proto::MapBuilderServerOptions& map_builder_server_options,
|
const proto::MapBuilderServerOptions& map_builder_server_options,
|
||||||
std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder);
|
std::unique_ptr<mapping::MapBuilderInterface> map_builder);
|
||||||
~MapBuilderServer() {}
|
~MapBuilderServer() {}
|
||||||
|
|
||||||
// Starts the gRPC server, the 'LocalTrajectoryUploader' and the SLAM thread.
|
// Starts the gRPC server, the 'LocalTrajectoryUploader' and the SLAM thread.
|
||||||
|
@ -64,11 +65,10 @@ class MapBuilderServer : public MapBuilderServerInterface {
|
||||||
void ProcessSensorDataQueue();
|
void ProcessSensorDataQueue();
|
||||||
void StartSlamThread();
|
void StartSlamThread();
|
||||||
void OnLocalSlamResult(
|
void OnLocalSlamResult(
|
||||||
int trajectory_id, cartographer::common::Time time,
|
int trajectory_id, common::Time time, transform::Rigid3d local_pose,
|
||||||
cartographer::transform::Rigid3d local_pose,
|
sensor::RangeData range_data,
|
||||||
cartographer::sensor::RangeData range_data,
|
std::unique_ptr<
|
||||||
std::unique_ptr<const cartographer::mapping::TrajectoryBuilderInterface::
|
const mapping::TrajectoryBuilderInterface::InsertionResult>
|
||||||
InsertionResult>
|
|
||||||
insertion_result);
|
insertion_result);
|
||||||
MapBuilderContextInterface::SubscriptionId SubscribeLocalSlamResults(
|
MapBuilderContextInterface::SubscriptionId SubscribeLocalSlamResults(
|
||||||
int trajectory_id,
|
int trajectory_id,
|
||||||
|
@ -80,11 +80,10 @@ class MapBuilderServer : public MapBuilderServerInterface {
|
||||||
bool shutting_down_ = false;
|
bool shutting_down_ = false;
|
||||||
std::unique_ptr<std::thread> slam_thread_;
|
std::unique_ptr<std::thread> slam_thread_;
|
||||||
std::unique_ptr<framework::Server> grpc_server_;
|
std::unique_ptr<framework::Server> grpc_server_;
|
||||||
std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder_;
|
std::unique_ptr<mapping::MapBuilderInterface> map_builder_;
|
||||||
cartographer::common::BlockingQueue<
|
common::BlockingQueue<std::unique_ptr<MapBuilderContextInterface::Data>>
|
||||||
std::unique_ptr<MapBuilderContextInterface::Data>>
|
|
||||||
incoming_data_queue_;
|
incoming_data_queue_;
|
||||||
cartographer::common::Mutex local_slam_subscriptions_lock_;
|
common::Mutex local_slam_subscriptions_lock_;
|
||||||
int current_subscription_index_ = 0;
|
int current_subscription_index_ = 0;
|
||||||
std::map<int /* trajectory ID */, LocalSlamResultHandlerSubscriptions>
|
std::map<int /* trajectory ID */, LocalSlamResultHandlerSubscriptions>
|
||||||
local_slam_subscriptions_ GUARDED_BY(local_slam_subscriptions_lock_);
|
local_slam_subscriptions_ GUARDED_BY(local_slam_subscriptions_lock_);
|
||||||
|
@ -92,6 +91,7 @@ class MapBuilderServer : public MapBuilderServerInterface {
|
||||||
int starting_submap_index_ = 0;
|
int starting_submap_index_ = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_SERVER_H
|
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_SERVER_H
|
||||||
|
|
|
@ -16,8 +16,8 @@
|
||||||
|
|
||||||
#include "cartographer_grpc/internal/sensor/serialization.h"
|
#include "cartographer_grpc/internal/sensor/serialization.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
namespace sensor {
|
namespace cloud {
|
||||||
|
|
||||||
void CreateSensorMetadata(const std::string& sensor_id, const int trajectory_id,
|
void CreateSensorMetadata(const std::string& sensor_id, const int trajectory_id,
|
||||||
proto::SensorMetadata* proto) {
|
proto::SensorMetadata* proto) {
|
||||||
|
@ -27,18 +27,17 @@ void CreateSensorMetadata(const std::string& sensor_id, const int trajectory_id,
|
||||||
|
|
||||||
void CreateAddFixedFramePoseDataRequest(
|
void CreateAddFixedFramePoseDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id,
|
||||||
const cartographer::sensor::proto::FixedFramePoseData&
|
const sensor::proto::FixedFramePoseData& fixed_frame_pose_data,
|
||||||
fixed_frame_pose_data,
|
|
||||||
proto::AddFixedFramePoseDataRequest* proto) {
|
proto::AddFixedFramePoseDataRequest* proto) {
|
||||||
CreateSensorMetadata(sensor_id, trajectory_id,
|
CreateSensorMetadata(sensor_id, trajectory_id,
|
||||||
proto->mutable_sensor_metadata());
|
proto->mutable_sensor_metadata());
|
||||||
*proto->mutable_fixed_frame_pose_data() = fixed_frame_pose_data;
|
*proto->mutable_fixed_frame_pose_data() = fixed_frame_pose_data;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CreateAddImuDataRequest(
|
void CreateAddImuDataRequest(const std::string& sensor_id,
|
||||||
const std::string& sensor_id, const int trajectory_id,
|
const int trajectory_id,
|
||||||
const cartographer::sensor::proto::ImuData& imu_data,
|
const sensor::proto::ImuData& imu_data,
|
||||||
proto::AddImuDataRequest* proto) {
|
proto::AddImuDataRequest* proto) {
|
||||||
CreateSensorMetadata(sensor_id, trajectory_id,
|
CreateSensorMetadata(sensor_id, trajectory_id,
|
||||||
proto->mutable_sensor_metadata());
|
proto->mutable_sensor_metadata());
|
||||||
*proto->mutable_imu_data() = imu_data;
|
*proto->mutable_imu_data() = imu_data;
|
||||||
|
@ -46,7 +45,7 @@ void CreateAddImuDataRequest(
|
||||||
|
|
||||||
void CreateAddOdometryDataRequest(
|
void CreateAddOdometryDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id,
|
||||||
const cartographer::sensor::proto::OdometryData& odometry_data,
|
const sensor::proto::OdometryData& odometry_data,
|
||||||
proto::AddOdometryDataRequest* proto) {
|
proto::AddOdometryDataRequest* proto) {
|
||||||
CreateSensorMetadata(sensor_id, trajectory_id,
|
CreateSensorMetadata(sensor_id, trajectory_id,
|
||||||
proto->mutable_sensor_metadata());
|
proto->mutable_sensor_metadata());
|
||||||
|
@ -55,8 +54,7 @@ void CreateAddOdometryDataRequest(
|
||||||
|
|
||||||
void CreateAddRangeFinderDataRequest(
|
void CreateAddRangeFinderDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id,
|
||||||
const cartographer::sensor::proto::TimedPointCloudData&
|
const sensor::proto::TimedPointCloudData& timed_point_cloud_data,
|
||||||
timed_point_cloud_data,
|
|
||||||
proto::AddRangefinderDataRequest* proto) {
|
proto::AddRangefinderDataRequest* proto) {
|
||||||
CreateSensorMetadata(sensor_id, trajectory_id,
|
CreateSensorMetadata(sensor_id, trajectory_id,
|
||||||
proto->mutable_sensor_metadata());
|
proto->mutable_sensor_metadata());
|
||||||
|
@ -65,7 +63,7 @@ void CreateAddRangeFinderDataRequest(
|
||||||
|
|
||||||
void CreateAddLandmarkDataRequest(
|
void CreateAddLandmarkDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id,
|
||||||
const cartographer::sensor::proto::LandmarkData& landmark_data,
|
const sensor::proto::LandmarkData& landmark_data,
|
||||||
proto::AddLandmarkDataRequest* proto) {
|
proto::AddLandmarkDataRequest* proto) {
|
||||||
CreateSensorMetadata(sensor_id, trajectory_id,
|
CreateSensorMetadata(sensor_id, trajectory_id,
|
||||||
proto->mutable_sensor_metadata());
|
proto->mutable_sensor_metadata());
|
||||||
|
@ -73,17 +71,17 @@ void CreateAddLandmarkDataRequest(
|
||||||
}
|
}
|
||||||
|
|
||||||
void CreateAddLocalSlamResultDataRequest(
|
void CreateAddLocalSlamResultDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id, common::Time time,
|
||||||
cartographer::common::Time time, int starting_submap_index,
|
int starting_submap_index,
|
||||||
const cartographer::mapping::TrajectoryBuilderInterface::InsertionResult&
|
const mapping::TrajectoryBuilderInterface::InsertionResult&
|
||||||
insertion_result,
|
insertion_result,
|
||||||
proto::AddLocalSlamResultDataRequest* proto) {
|
proto::AddLocalSlamResultDataRequest* proto) {
|
||||||
sensor::CreateSensorMetadata(sensor_id, trajectory_id,
|
CreateSensorMetadata(sensor_id, trajectory_id,
|
||||||
proto->mutable_sensor_metadata());
|
proto->mutable_sensor_metadata());
|
||||||
proto->mutable_local_slam_result_data()->set_timestamp(
|
proto->mutable_local_slam_result_data()->set_timestamp(
|
||||||
cartographer::common::ToUniversal(time));
|
common::ToUniversal(time));
|
||||||
*proto->mutable_local_slam_result_data()->mutable_node_data() =
|
*proto->mutable_local_slam_result_data()->mutable_node_data() =
|
||||||
cartographer::mapping::ToProto(*insertion_result.constant_data);
|
mapping::ToProto(*insertion_result.constant_data);
|
||||||
for (const auto& insertion_submap : insertion_result.insertion_submaps) {
|
for (const auto& insertion_submap : insertion_result.insertion_submaps) {
|
||||||
// We only send the probability grid up if the submap is finished.
|
// We only send the probability grid up if the submap is finished.
|
||||||
auto* submap = proto->mutable_local_slam_result_data()->add_submaps();
|
auto* submap = proto->mutable_local_slam_result_data()->add_submaps();
|
||||||
|
@ -95,10 +93,8 @@ void CreateAddLocalSlamResultDataRequest(
|
||||||
}
|
}
|
||||||
|
|
||||||
proto::SensorId ToProto(
|
proto::SensorId ToProto(
|
||||||
const cartographer::mapping::TrajectoryBuilderInterface::SensorId&
|
const mapping::TrajectoryBuilderInterface::SensorId& sensor_id) {
|
||||||
sensor_id) {
|
using SensorType = mapping::TrajectoryBuilderInterface::SensorId::SensorType;
|
||||||
using SensorType =
|
|
||||||
cartographer::mapping::TrajectoryBuilderInterface::SensorId::SensorType;
|
|
||||||
proto::SensorType type;
|
proto::SensorType type;
|
||||||
switch (sensor_id.type) {
|
switch (sensor_id.type) {
|
||||||
case SensorType::RANGE:
|
case SensorType::RANGE:
|
||||||
|
@ -128,9 +124,9 @@ proto::SensorId ToProto(
|
||||||
return proto;
|
return proto;
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::mapping::TrajectoryBuilderInterface::SensorId FromProto(
|
mapping::TrajectoryBuilderInterface::SensorId FromProto(
|
||||||
const proto::SensorId& proto) {
|
const proto::SensorId& proto) {
|
||||||
using SensorId = cartographer::mapping::TrajectoryBuilderInterface::SensorId;
|
using SensorId = mapping::TrajectoryBuilderInterface::SensorId;
|
||||||
using SensorType = SensorId::SensorType;
|
using SensorType = SensorId::SensorType;
|
||||||
SensorType type;
|
SensorType type;
|
||||||
switch (proto.type()) {
|
switch (proto.type()) {
|
||||||
|
@ -158,5 +154,5 @@ cartographer::mapping::TrajectoryBuilderInterface::SensorId FromProto(
|
||||||
return SensorId{type, proto.id()};
|
return SensorId{type, proto.id()};
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace sensor
|
} // namespace cloud
|
||||||
} // namespace cartographer_grpc
|
} // namespace cartographer
|
||||||
|
|
|
@ -26,48 +26,44 @@
|
||||||
#include "cartographer/sensor/timed_point_cloud_data.h"
|
#include "cartographer/sensor/timed_point_cloud_data.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
namespace sensor {
|
namespace cloud {
|
||||||
|
|
||||||
void CreateSensorMetadata(const std::string& sensor_id, int trajectory_id,
|
void CreateSensorMetadata(const std::string& sensor_id, int trajectory_id,
|
||||||
proto::SensorMetadata* proto);
|
proto::SensorMetadata* proto);
|
||||||
|
|
||||||
void CreateAddFixedFramePoseDataRequest(
|
void CreateAddFixedFramePoseDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id,
|
||||||
const cartographer::sensor::proto::FixedFramePoseData&
|
const sensor::proto::FixedFramePoseData& fixed_frame_pose_data,
|
||||||
fixed_frame_pose_data,
|
|
||||||
proto::AddFixedFramePoseDataRequest* proto);
|
proto::AddFixedFramePoseDataRequest* proto);
|
||||||
void CreateAddImuDataRequest(
|
void CreateAddImuDataRequest(const std::string& sensor_id, int trajectory_id,
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const sensor::proto::ImuData& imu_data,
|
||||||
const cartographer::sensor::proto::ImuData& imu_data,
|
proto::AddImuDataRequest* proto);
|
||||||
proto::AddImuDataRequest* proto);
|
|
||||||
void CreateAddOdometryDataRequest(
|
void CreateAddOdometryDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id,
|
||||||
const cartographer::sensor::proto::OdometryData& odometry_data,
|
const sensor::proto::OdometryData& odometry_data,
|
||||||
proto::AddOdometryDataRequest* proto);
|
proto::AddOdometryDataRequest* proto);
|
||||||
void CreateAddRangeFinderDataRequest(
|
void CreateAddRangeFinderDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id,
|
||||||
const cartographer::sensor::proto::TimedPointCloudData&
|
const sensor::proto::TimedPointCloudData& timed_point_cloud_data,
|
||||||
timed_point_cloud_data,
|
|
||||||
proto::AddRangefinderDataRequest* proto);
|
proto::AddRangefinderDataRequest* proto);
|
||||||
void CreateAddLandmarkDataRequest(
|
void CreateAddLandmarkDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id,
|
||||||
const cartographer::sensor::proto::LandmarkData& landmark_data,
|
const sensor::proto::LandmarkData& landmark_data,
|
||||||
proto::AddLandmarkDataRequest* proto);
|
proto::AddLandmarkDataRequest* proto);
|
||||||
void CreateAddLocalSlamResultDataRequest(
|
void CreateAddLocalSlamResultDataRequest(
|
||||||
const std::string& sensor_id, int trajectory_id,
|
const std::string& sensor_id, int trajectory_id, common::Time time,
|
||||||
cartographer::common::Time time, int starting_submap_index,
|
int starting_submap_index,
|
||||||
const cartographer::mapping::TrajectoryBuilderInterface::InsertionResult&
|
const mapping::TrajectoryBuilderInterface::InsertionResult&
|
||||||
insertion_result,
|
insertion_result,
|
||||||
proto::AddLocalSlamResultDataRequest* proto);
|
proto::AddLocalSlamResultDataRequest* proto);
|
||||||
|
|
||||||
proto::SensorId ToProto(
|
proto::SensorId ToProto(
|
||||||
const cartographer::mapping::TrajectoryBuilderInterface::SensorId&
|
const mapping::TrajectoryBuilderInterface::SensorId& sensor_id);
|
||||||
sensor_id);
|
mapping::TrajectoryBuilderInterface::SensorId FromProto(
|
||||||
cartographer::mapping::TrajectoryBuilderInterface::SensorId FromProto(
|
|
||||||
const proto::SensorId& proto);
|
const proto::SensorId& proto);
|
||||||
|
|
||||||
} // namespace sensor
|
} // namespace cloud
|
||||||
} // namespace cartographer_grpc
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_SENSOR_SERIALIZATION_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_SENSOR_SERIALIZATION_H
|
||||||
|
|
|
@ -25,7 +25,8 @@
|
||||||
#include "mock_map_builder_context.h"
|
#include "mock_map_builder_context.h"
|
||||||
#include "mock_pose_graph.h"
|
#include "mock_pose_graph.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
using ::testing::Return;
|
using ::testing::Return;
|
||||||
|
@ -35,16 +36,16 @@ template <typename HandlerType>
|
||||||
class HandlerTest : public Test {
|
class HandlerTest : public Test {
|
||||||
public:
|
public:
|
||||||
void SetUp() override {
|
void SetUp() override {
|
||||||
test_server_ = cartographer::common::make_unique<
|
test_server_ = common::make_unique<
|
||||||
framework::testing::RpcHandlerTestServer<HandlerType>>(
|
framework::testing::RpcHandlerTestServer<HandlerType>>(
|
||||||
cartographer::common::make_unique<MockMapBuilderContext>());
|
common::make_unique<MockMapBuilderContext>());
|
||||||
mock_map_builder_context_ =
|
mock_map_builder_context_ =
|
||||||
test_server_
|
test_server_
|
||||||
->template GetUnsynchronizedContext<MockMapBuilderContext>();
|
->template GetUnsynchronizedContext<MockMapBuilderContext>();
|
||||||
mock_local_trajectory_uploader_ =
|
mock_local_trajectory_uploader_ =
|
||||||
cartographer::common::make_unique<MockLocalTrajectoryUploader>();
|
common::make_unique<MockLocalTrajectoryUploader>();
|
||||||
mock_map_builder_ = cartographer::common::make_unique<MockMapBuilder>();
|
mock_map_builder_ = common::make_unique<MockMapBuilder>();
|
||||||
mock_pose_graph_ = cartographer::common::make_unique<MockPoseGraph>();
|
mock_pose_graph_ = common::make_unique<MockPoseGraph>();
|
||||||
|
|
||||||
EXPECT_CALL(*mock_map_builder_context_, map_builder())
|
EXPECT_CALL(*mock_map_builder_context_, map_builder())
|
||||||
.Times(::testing::AnyNumber())
|
.Times(::testing::AnyNumber())
|
||||||
|
@ -74,6 +75,7 @@ class HandlerTest : public Test {
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_HANDLER_TEST_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_HANDLER_TEST_H
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "gmock/gmock.h"
|
#include "gmock/gmock.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
class MockLocalTrajectoryUploader : public LocalTrajectoryUploaderInterface {
|
class MockLocalTrajectoryUploader : public LocalTrajectoryUploaderInterface {
|
||||||
|
@ -34,15 +35,15 @@ class MockLocalTrajectoryUploader : public LocalTrajectoryUploaderInterface {
|
||||||
}
|
}
|
||||||
MOCK_METHOD0(Start, void());
|
MOCK_METHOD0(Start, void());
|
||||||
MOCK_METHOD0(Shutdown, void());
|
MOCK_METHOD0(Shutdown, void());
|
||||||
MOCK_METHOD3(
|
MOCK_METHOD3(AddTrajectory,
|
||||||
AddTrajectory,
|
void(int, const std::set<SensorId> &,
|
||||||
void(int, const std::set<SensorId> &,
|
const mapping::proto::TrajectoryBuilderOptions &));
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptions &));
|
|
||||||
MOCK_METHOD1(FinishTrajectory, void(int));
|
MOCK_METHOD1(FinishTrajectory, void(int));
|
||||||
MOCK_CONST_METHOD1(GetLocalSlamResultSensorId, SensorId(int));
|
MOCK_CONST_METHOD1(GetLocalSlamResultSensorId, SensorId(int));
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_LOCAL_TRAJECTORY_UPLOADER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_LOCAL_TRAJECTORY_UPLOADER_H
|
||||||
|
|
|
@ -25,44 +25,39 @@
|
||||||
|
|
||||||
using testing::_;
|
using testing::_;
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
class MockMapBuilder : public cartographer::mapping::MapBuilderInterface {
|
class MockMapBuilder : public mapping::MapBuilderInterface {
|
||||||
public:
|
public:
|
||||||
MOCK_METHOD3(
|
MOCK_METHOD3(
|
||||||
AddTrajectoryBuilder,
|
AddTrajectoryBuilder,
|
||||||
int(const std::set<SensorId> &expected_sensor_ids,
|
int(const std::set<SensorId> &expected_sensor_ids,
|
||||||
const cartographer::mapping::proto::TrajectoryBuilderOptions
|
const mapping::proto::TrajectoryBuilderOptions &trajectory_options,
|
||||||
&trajectory_options,
|
mapping::MapBuilderInterface::LocalSlamResultCallback
|
||||||
cartographer::mapping::MapBuilderInterface::LocalSlamResultCallback
|
|
||||||
local_slam_result_callback));
|
local_slam_result_callback));
|
||||||
MOCK_METHOD1(AddTrajectoryForDeserialization,
|
MOCK_METHOD1(AddTrajectoryForDeserialization,
|
||||||
int(const cartographer::mapping::proto::
|
int(const mapping::proto::TrajectoryBuilderOptionsWithSensorIds
|
||||||
TrajectoryBuilderOptionsWithSensorIds
|
&options_with_sensor_ids_proto));
|
||||||
&options_with_sensor_ids_proto));
|
MOCK_CONST_METHOD1(GetTrajectoryBuilder,
|
||||||
MOCK_CONST_METHOD1(
|
mapping::TrajectoryBuilderInterface *(int trajectory_id));
|
||||||
GetTrajectoryBuilder,
|
|
||||||
cartographer::mapping::TrajectoryBuilderInterface *(int trajectory_id));
|
|
||||||
MOCK_METHOD1(FinishTrajectory, void(int trajectory_id));
|
MOCK_METHOD1(FinishTrajectory, void(int trajectory_id));
|
||||||
MOCK_METHOD2(
|
MOCK_METHOD2(SubmapToProto,
|
||||||
SubmapToProto,
|
std::string(const mapping::SubmapId &,
|
||||||
std::string(const cartographer::mapping::SubmapId &,
|
mapping::proto::SubmapQuery::Response *));
|
||||||
cartographer::mapping::proto::SubmapQuery::Response *));
|
MOCK_METHOD1(SerializeState, void(io::ProtoStreamWriterInterface *));
|
||||||
MOCK_METHOD1(SerializeState,
|
MOCK_METHOD2(LoadState, void(io::ProtoStreamReaderInterface *, bool));
|
||||||
void(cartographer::io::ProtoStreamWriterInterface *));
|
|
||||||
MOCK_METHOD2(LoadState,
|
|
||||||
void(cartographer::io::ProtoStreamReaderInterface *, bool));
|
|
||||||
MOCK_CONST_METHOD0(num_trajectory_builders, int());
|
MOCK_CONST_METHOD0(num_trajectory_builders, int());
|
||||||
MOCK_METHOD0(pose_graph, cartographer::mapping::PoseGraphInterface *());
|
MOCK_METHOD0(pose_graph, mapping::PoseGraphInterface *());
|
||||||
MOCK_CONST_METHOD0(
|
MOCK_CONST_METHOD0(
|
||||||
GetAllTrajectoryBuilderOptions,
|
GetAllTrajectoryBuilderOptions,
|
||||||
const std::vector<
|
const std::vector<mapping::proto::TrajectoryBuilderOptionsWithSensorIds>
|
||||||
cartographer::mapping::proto::TrajectoryBuilderOptionsWithSensorIds>
|
|
||||||
&());
|
&());
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_MAP_BUILDER_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_MAP_BUILDER_H
|
||||||
|
|
|
@ -23,18 +23,19 @@
|
||||||
#include "gmock/gmock.h"
|
#include "gmock/gmock.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
class MockMapBuilderContext : public MapBuilderContextInterface {
|
class MockMapBuilderContext : public MapBuilderContextInterface {
|
||||||
public:
|
public:
|
||||||
MOCK_METHOD0(map_builder, cartographer::mapping::MapBuilderInterface &());
|
MOCK_METHOD0(map_builder, mapping::MapBuilderInterface &());
|
||||||
MOCK_METHOD0(sensor_data_queue,
|
MOCK_METHOD0(
|
||||||
cartographer::common::BlockingQueue<
|
sensor_data_queue,
|
||||||
std::unique_ptr<MapBuilderContextInterface::Data>> &());
|
common::BlockingQueue<std::unique_ptr<MapBuilderContextInterface::Data>>
|
||||||
|
&());
|
||||||
MOCK_METHOD0(GetLocalSlamResultCallbackForSubscriptions,
|
MOCK_METHOD0(GetLocalSlamResultCallbackForSubscriptions,
|
||||||
cartographer::mapping::TrajectoryBuilderInterface::
|
mapping::TrajectoryBuilderInterface::LocalSlamResultCallback());
|
||||||
LocalSlamResultCallback());
|
|
||||||
MOCK_METHOD1(AddSensorDataToTrajectory,
|
MOCK_METHOD1(AddSensorDataToTrajectory,
|
||||||
void(const MapBuilderContextInterface::Data &));
|
void(const MapBuilderContextInterface::Data &));
|
||||||
MOCK_METHOD2(SubscribeLocalSlamResults,
|
MOCK_METHOD2(SubscribeLocalSlamResults,
|
||||||
|
@ -45,37 +46,35 @@ class MockMapBuilderContext : public MapBuilderContextInterface {
|
||||||
void(const MapBuilderContextInterface::SubscriptionId &));
|
void(const MapBuilderContextInterface::SubscriptionId &));
|
||||||
MOCK_METHOD1(NotifyFinishTrajectory, void(int));
|
MOCK_METHOD1(NotifyFinishTrajectory, void(int));
|
||||||
MOCK_METHOD3(DoProcessLocalSlamResultData,
|
MOCK_METHOD3(DoProcessLocalSlamResultData,
|
||||||
cartographer::mapping::LocalSlamResultData *(
|
mapping::LocalSlamResultData *(
|
||||||
const std::string &, cartographer::common::Time,
|
const std::string &, common::Time,
|
||||||
const cartographer::mapping::proto::LocalSlamResultData &));
|
const mapping::proto::LocalSlamResultData &));
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
std::unique_ptr<mapping::LocalSlamResultData> ProcessLocalSlamResultData(
|
||||||
ProcessLocalSlamResultData(
|
const std::string &sensor_id, common::Time time,
|
||||||
const std::string &sensor_id, cartographer::common::Time time,
|
const mapping::proto::LocalSlamResultData &proto) override {
|
||||||
const cartographer::mapping::proto::LocalSlamResultData &proto) override {
|
return std::unique_ptr<mapping::LocalSlamResultData>(
|
||||||
return std::unique_ptr<cartographer::mapping::LocalSlamResultData>(
|
|
||||||
DoProcessLocalSlamResultData(sensor_id, time, proto));
|
DoProcessLocalSlamResultData(sensor_id, time, proto));
|
||||||
}
|
}
|
||||||
MOCK_METHOD0(local_trajectory_uploader, LocalTrajectoryUploaderInterface *());
|
MOCK_METHOD0(local_trajectory_uploader, LocalTrajectoryUploaderInterface *());
|
||||||
|
|
||||||
MOCK_METHOD2(DoEnqueueSensorData, void(int, cartographer::sensor::Data *));
|
MOCK_METHOD2(DoEnqueueSensorData, void(int, sensor::Data *));
|
||||||
void EnqueueSensorData(
|
void EnqueueSensorData(int trajectory_id,
|
||||||
int trajectory_id,
|
std::unique_ptr<sensor::Data> data) override {
|
||||||
std::unique_ptr<cartographer::sensor::Data> data) override {
|
|
||||||
DoEnqueueSensorData(trajectory_id, data.get());
|
DoEnqueueSensorData(trajectory_id, data.get());
|
||||||
}
|
}
|
||||||
MOCK_METHOD3(DoEnqueueLocalSlamResultData,
|
MOCK_METHOD3(DoEnqueueLocalSlamResultData,
|
||||||
void(int, const std::string &,
|
void(int, const std::string &, mapping::LocalSlamResultData *));
|
||||||
cartographer::mapping::LocalSlamResultData *));
|
void EnqueueLocalSlamResultData(int trajectory_id,
|
||||||
void EnqueueLocalSlamResultData(
|
const std::string &sensor_id,
|
||||||
int trajectory_id, const std::string &sensor_id,
|
std::unique_ptr<mapping::LocalSlamResultData>
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
local_slam_result_data) override {
|
||||||
local_slam_result_data) override {
|
|
||||||
DoEnqueueLocalSlamResultData(trajectory_id, sensor_id,
|
DoEnqueueLocalSlamResultData(trajectory_id, sensor_id,
|
||||||
local_slam_result_data.get());
|
local_slam_result_data.get());
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_MAP_BUILDER_CONTEXT_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_MAP_BUILDER_CONTEXT_H
|
||||||
|
|
|
@ -22,43 +22,36 @@
|
||||||
#include "gmock/gmock.h"
|
#include "gmock/gmock.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
class MockPoseGraph : public cartographer::mapping::PoseGraphInterface {
|
class MockPoseGraph : public mapping::PoseGraphInterface {
|
||||||
public:
|
public:
|
||||||
MockPoseGraph() = default;
|
MockPoseGraph() = default;
|
||||||
~MockPoseGraph() override = default;
|
~MockPoseGraph() override = default;
|
||||||
|
|
||||||
MOCK_METHOD0(RunFinalOptimization, void());
|
MOCK_METHOD0(RunFinalOptimization, void());
|
||||||
MOCK_METHOD0(GetAllSubmapData,
|
MOCK_METHOD0(GetAllSubmapData,
|
||||||
cartographer::mapping::MapById<cartographer::mapping::SubmapId,
|
mapping::MapById<mapping::SubmapId, SubmapData>());
|
||||||
SubmapData>());
|
|
||||||
MOCK_METHOD0(GetAllSubmapPoses,
|
MOCK_METHOD0(GetAllSubmapPoses,
|
||||||
cartographer::mapping::MapById<cartographer::mapping::SubmapId,
|
mapping::MapById<mapping::SubmapId, SubmapPose>());
|
||||||
SubmapPose>());
|
MOCK_METHOD1(GetLocalToGlobalTransform, transform::Rigid3d(int));
|
||||||
MOCK_METHOD1(GetLocalToGlobalTransform,
|
MOCK_METHOD0(GetTrajectoryNodes,
|
||||||
cartographer::transform::Rigid3d(int));
|
mapping::MapById<mapping::NodeId, mapping::TrajectoryNode>());
|
||||||
MOCK_METHOD0(
|
MOCK_METHOD0(
|
||||||
GetTrajectoryNodes,
|
GetTrajectoryNodePoses,
|
||||||
cartographer::mapping::MapById<cartographer::mapping::NodeId,
|
mapping::MapById<mapping::NodeId, mapping::TrajectoryNodePose>());
|
||||||
cartographer::mapping::TrajectoryNode>());
|
MOCK_METHOD0(GetLandmarkPoses, std::map<std::string, transform::Rigid3d>());
|
||||||
MOCK_METHOD0(GetTrajectoryNodePoses,
|
|
||||||
cartographer::mapping::MapById<
|
|
||||||
cartographer::mapping::NodeId,
|
|
||||||
cartographer::mapping::TrajectoryNodePose>());
|
|
||||||
MOCK_METHOD0(GetLandmarkPoses,
|
|
||||||
std::map<std::string, cartographer::transform::Rigid3d>());
|
|
||||||
MOCK_METHOD1(IsTrajectoryFinished, bool(int));
|
MOCK_METHOD1(IsTrajectoryFinished, bool(int));
|
||||||
MOCK_METHOD0(
|
MOCK_METHOD0(GetTrajectoryData,
|
||||||
GetTrajectoryData,
|
std::map<int, mapping::PoseGraphInterface::TrajectoryData>());
|
||||||
std::map<int,
|
|
||||||
cartographer::mapping::PoseGraphInterface::TrajectoryData>());
|
|
||||||
MOCK_METHOD0(constraints, std::vector<Constraint>());
|
MOCK_METHOD0(constraints, std::vector<Constraint>());
|
||||||
MOCK_METHOD0(ToProto, cartographer::mapping::proto::PoseGraph());
|
MOCK_METHOD0(ToProto, mapping::proto::PoseGraph());
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_POSE_GRAPH_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_POSE_GRAPH_H
|
||||||
|
|
|
@ -22,40 +22,37 @@
|
||||||
#include "gmock/gmock.h"
|
#include "gmock/gmock.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
class MockTrajectoryBuilder
|
class MockTrajectoryBuilder : public mapping::TrajectoryBuilderInterface {
|
||||||
: public cartographer::mapping::TrajectoryBuilderInterface {
|
|
||||||
public:
|
public:
|
||||||
MockTrajectoryBuilder() = default;
|
MockTrajectoryBuilder() = default;
|
||||||
~MockTrajectoryBuilder() override = default;
|
~MockTrajectoryBuilder() override = default;
|
||||||
|
|
||||||
MOCK_METHOD2(AddSensorData,
|
MOCK_METHOD2(AddSensorData,
|
||||||
void(const std::string &,
|
void(const std::string &, const sensor::TimedPointCloudData &));
|
||||||
const cartographer::sensor::TimedPointCloudData &));
|
|
||||||
MOCK_METHOD2(AddSensorData, void(const std::string &,
|
|
||||||
const cartographer::sensor::ImuData &));
|
|
||||||
MOCK_METHOD2(AddSensorData, void(const std::string &,
|
|
||||||
const cartographer::sensor::OdometryData &));
|
|
||||||
MOCK_METHOD2(AddSensorData,
|
MOCK_METHOD2(AddSensorData,
|
||||||
void(const std::string &,
|
void(const std::string &, const sensor::ImuData &));
|
||||||
const cartographer::sensor::FixedFramePoseData &));
|
MOCK_METHOD2(AddSensorData,
|
||||||
MOCK_METHOD2(AddSensorData, void(const std::string &,
|
void(const std::string &, const sensor::OdometryData &));
|
||||||
const cartographer::sensor::LandmarkData &));
|
MOCK_METHOD2(AddSensorData,
|
||||||
|
void(const std::string &, const sensor::FixedFramePoseData &));
|
||||||
|
MOCK_METHOD2(AddSensorData,
|
||||||
|
void(const std::string &, const sensor::LandmarkData &));
|
||||||
|
|
||||||
// Some of the platforms we run on may ship with a version of gmock which does
|
// Some of the platforms we run on may ship with a version of gmock which does
|
||||||
// not yet support move-only types.
|
// not yet support move-only types.
|
||||||
MOCK_METHOD1(DoAddLocalSlamResultData,
|
MOCK_METHOD1(DoAddLocalSlamResultData, void(mapping::LocalSlamResultData *));
|
||||||
void(cartographer::mapping::LocalSlamResultData *));
|
void AddLocalSlamResultData(std::unique_ptr<mapping::LocalSlamResultData>
|
||||||
void AddLocalSlamResultData(
|
local_slam_result_data) override {
|
||||||
std::unique_ptr<cartographer::mapping::LocalSlamResultData>
|
|
||||||
local_slam_result_data) override {
|
|
||||||
DoAddLocalSlamResultData(local_slam_result_data.get());
|
DoAddLocalSlamResultData(local_slam_result_data.get());
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_TRAJECTORY_BUILDER_CONTEXT_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_MOCK_TRAJECTORY_BUILDER_CONTEXT_H
|
||||||
|
|
|
@ -16,20 +16,19 @@
|
||||||
|
|
||||||
#include "cartographer_grpc/internal/testing/test_helpers.h"
|
#include "cartographer_grpc/internal/testing/test_helpers.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
template <>
|
template <>
|
||||||
DataPredicateType BuildDataPredicateEquals<proto::AddImuDataRequest>(
|
DataPredicateType BuildDataPredicateEquals<proto::AddImuDataRequest>(
|
||||||
const proto::AddImuDataRequest &proto) {
|
const proto::AddImuDataRequest &proto) {
|
||||||
return [proto](const cartographer::sensor::Data &data) {
|
return [proto](const sensor::Data &data) {
|
||||||
const auto *dispatchable =
|
const auto *dispatchable =
|
||||||
dynamic_cast<const cartographer::sensor::Dispatchable<
|
dynamic_cast<const sensor::Dispatchable<sensor::ImuData> *>(&data);
|
||||||
cartographer::sensor::ImuData> *>(&data);
|
|
||||||
CHECK_NOTNULL(dispatchable);
|
CHECK_NOTNULL(dispatchable);
|
||||||
return google::protobuf::util::MessageDifferencer::Equals(
|
return google::protobuf::util::MessageDifferencer::Equals(
|
||||||
cartographer::sensor::ToProto(dispatchable->data()),
|
sensor::ToProto(dispatchable->data()), proto.imu_data()) &&
|
||||||
proto.imu_data()) &&
|
|
||||||
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
@ -37,13 +36,13 @@ DataPredicateType BuildDataPredicateEquals<proto::AddImuDataRequest>(
|
||||||
template <>
|
template <>
|
||||||
DataPredicateType BuildDataPredicateEquals<proto::AddFixedFramePoseDataRequest>(
|
DataPredicateType BuildDataPredicateEquals<proto::AddFixedFramePoseDataRequest>(
|
||||||
const proto::AddFixedFramePoseDataRequest &proto) {
|
const proto::AddFixedFramePoseDataRequest &proto) {
|
||||||
return [proto](const cartographer::sensor::Data &data) {
|
return [proto](const sensor::Data &data) {
|
||||||
const auto *dispatchable =
|
const auto *dispatchable =
|
||||||
dynamic_cast<const cartographer::sensor::Dispatchable<
|
dynamic_cast<const sensor::Dispatchable<sensor::FixedFramePoseData> *>(
|
||||||
cartographer::sensor::FixedFramePoseData> *>(&data);
|
&data);
|
||||||
CHECK_NOTNULL(dispatchable);
|
CHECK_NOTNULL(dispatchable);
|
||||||
return google::protobuf::util::MessageDifferencer::Equals(
|
return google::protobuf::util::MessageDifferencer::Equals(
|
||||||
cartographer::sensor::ToProto(dispatchable->data()),
|
sensor::ToProto(dispatchable->data()),
|
||||||
proto.fixed_frame_pose_data()) &&
|
proto.fixed_frame_pose_data()) &&
|
||||||
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
||||||
};
|
};
|
||||||
|
@ -52,14 +51,12 @@ DataPredicateType BuildDataPredicateEquals<proto::AddFixedFramePoseDataRequest>(
|
||||||
template <>
|
template <>
|
||||||
DataPredicateType BuildDataPredicateEquals<proto::AddOdometryDataRequest>(
|
DataPredicateType BuildDataPredicateEquals<proto::AddOdometryDataRequest>(
|
||||||
const proto::AddOdometryDataRequest &proto) {
|
const proto::AddOdometryDataRequest &proto) {
|
||||||
return [proto](const cartographer::sensor::Data &data) {
|
return [proto](const sensor::Data &data) {
|
||||||
const auto *dispatchable =
|
const auto *dispatchable =
|
||||||
dynamic_cast<const cartographer::sensor::Dispatchable<
|
dynamic_cast<const sensor::Dispatchable<sensor::OdometryData> *>(&data);
|
||||||
cartographer::sensor::OdometryData> *>(&data);
|
|
||||||
CHECK_NOTNULL(dispatchable);
|
CHECK_NOTNULL(dispatchable);
|
||||||
return google::protobuf::util::MessageDifferencer::Equals(
|
return google::protobuf::util::MessageDifferencer::Equals(
|
||||||
cartographer::sensor::ToProto(dispatchable->data()),
|
sensor::ToProto(dispatchable->data()), proto.odometry_data()) &&
|
||||||
proto.odometry_data()) &&
|
|
||||||
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
@ -67,14 +64,12 @@ DataPredicateType BuildDataPredicateEquals<proto::AddOdometryDataRequest>(
|
||||||
template <>
|
template <>
|
||||||
DataPredicateType BuildDataPredicateEquals<proto::AddLandmarkDataRequest>(
|
DataPredicateType BuildDataPredicateEquals<proto::AddLandmarkDataRequest>(
|
||||||
const proto::AddLandmarkDataRequest &proto) {
|
const proto::AddLandmarkDataRequest &proto) {
|
||||||
return [proto](const cartographer::sensor::Data &data) {
|
return [proto](const sensor::Data &data) {
|
||||||
const auto *dispatchable =
|
const auto *dispatchable =
|
||||||
dynamic_cast<const cartographer::sensor::Dispatchable<
|
dynamic_cast<const sensor::Dispatchable<sensor::LandmarkData> *>(&data);
|
||||||
cartographer::sensor::LandmarkData> *>(&data);
|
|
||||||
CHECK_NOTNULL(dispatchable);
|
CHECK_NOTNULL(dispatchable);
|
||||||
return google::protobuf::util::MessageDifferencer::Equals(
|
return google::protobuf::util::MessageDifferencer::Equals(
|
||||||
cartographer::sensor::ToProto(dispatchable->data()),
|
sensor::ToProto(dispatchable->data()), proto.landmark_data()) &&
|
||||||
proto.landmark_data()) &&
|
|
||||||
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
@ -82,13 +77,13 @@ DataPredicateType BuildDataPredicateEquals<proto::AddLandmarkDataRequest>(
|
||||||
template <>
|
template <>
|
||||||
DataPredicateType BuildDataPredicateEquals<proto::AddRangefinderDataRequest>(
|
DataPredicateType BuildDataPredicateEquals<proto::AddRangefinderDataRequest>(
|
||||||
const proto::AddRangefinderDataRequest &proto) {
|
const proto::AddRangefinderDataRequest &proto) {
|
||||||
return [proto](const cartographer::sensor::Data &data) {
|
return [proto](const sensor::Data &data) {
|
||||||
const auto *dispatchable =
|
const auto *dispatchable =
|
||||||
dynamic_cast<const cartographer::sensor::Dispatchable<
|
dynamic_cast<const sensor::Dispatchable<sensor::TimedPointCloudData> *>(
|
||||||
cartographer::sensor::TimedPointCloudData> *>(&data);
|
&data);
|
||||||
CHECK_NOTNULL(dispatchable);
|
CHECK_NOTNULL(dispatchable);
|
||||||
return google::protobuf::util::MessageDifferencer::Equals(
|
return google::protobuf::util::MessageDifferencer::Equals(
|
||||||
cartographer::sensor::ToProto(dispatchable->data()),
|
sensor::ToProto(dispatchable->data()),
|
||||||
proto.timed_point_cloud_data()) &&
|
proto.timed_point_cloud_data()) &&
|
||||||
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
dispatchable->GetSensorId() == proto.sensor_metadata().sensor_id();
|
||||||
};
|
};
|
||||||
|
@ -102,4 +97,5 @@ ProtoPredicateType BuildProtoPredicateEquals(
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -21,11 +21,11 @@
|
||||||
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
#include "cartographer_grpc/proto/map_builder_service.pb.h"
|
||||||
#include "google/protobuf/util/message_differencer.h"
|
#include "google/protobuf/util/message_differencer.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace testing {
|
namespace testing {
|
||||||
|
|
||||||
using DataPredicateType =
|
using DataPredicateType = std::function<bool(const sensor::Data &)>;
|
||||||
std::function<bool(const cartographer::sensor::Data &)>;
|
|
||||||
using ProtoPredicateType =
|
using ProtoPredicateType =
|
||||||
std::function<bool(const google::protobuf::Message &)>;
|
std::function<bool(const google::protobuf::Message &)>;
|
||||||
|
|
||||||
|
@ -52,6 +52,7 @@ ProtoPredicateType BuildProtoPredicateEquals(
|
||||||
const google::protobuf::Message *proto);
|
const google::protobuf::Message *proto);
|
||||||
|
|
||||||
} // namespace testing
|
} // namespace testing
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_TEST_HELPERS_H
|
#endif // CARTOGRAPHER_GRPC_INTERNAL_TESTING_TEST_HELPERS_H
|
||||||
|
|
|
@ -3,13 +3,15 @@
|
||||||
#include "cartographer/common/make_unique.h"
|
#include "cartographer/common/make_unique.h"
|
||||||
#include "cartographer_grpc/internal/map_builder_server.h"
|
#include "cartographer_grpc/internal/map_builder_server.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
std::unique_ptr<MapBuilderServerInterface> CreateMapBuilderServer(
|
std::unique_ptr<MapBuilderServerInterface> CreateMapBuilderServer(
|
||||||
const proto::MapBuilderServerOptions& map_builder_server_options,
|
const proto::MapBuilderServerOptions& map_builder_server_options,
|
||||||
std::unique_ptr<::cartographer::mapping::MapBuilderInterface> map_builder) {
|
std::unique_ptr<mapping::MapBuilderInterface> map_builder) {
|
||||||
return ::cartographer::common::make_unique<MapBuilderServer>(
|
return common::make_unique<MapBuilderServer>(map_builder_server_options,
|
||||||
map_builder_server_options, std::move(map_builder));
|
std::move(map_builder));
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -22,7 +22,8 @@
|
||||||
#include "cartographer/mapping/map_builder_interface.h"
|
#include "cartographer/mapping/map_builder_interface.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_server_options.pb.h"
|
#include "cartographer_grpc/proto/map_builder_server_options.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
class MapBuilderServerInterface {
|
class MapBuilderServerInterface {
|
||||||
public:
|
public:
|
||||||
|
@ -47,8 +48,9 @@ class MapBuilderServerInterface {
|
||||||
// Returns MapBuilderServer with the actual implementation.
|
// Returns MapBuilderServer with the actual implementation.
|
||||||
std::unique_ptr<MapBuilderServerInterface> CreateMapBuilderServer(
|
std::unique_ptr<MapBuilderServerInterface> CreateMapBuilderServer(
|
||||||
const proto::MapBuilderServerOptions& map_builder_server_options,
|
const proto::MapBuilderServerOptions& map_builder_server_options,
|
||||||
std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder);
|
std::unique_ptr<mapping::MapBuilderInterface> map_builder);
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_SERVER_INTERFACE_H
|
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_SERVER_INTERFACE_H
|
||||||
|
|
|
@ -33,13 +33,14 @@ DEFINE_string(configuration_basename, "",
|
||||||
"Basename, i.e. not containing any directory prefix, of the "
|
"Basename, i.e. not containing any directory prefix, of the "
|
||||||
"configuration file.");
|
"configuration file.");
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
void Run(const std::string& configuration_directory,
|
void Run(const std::string& configuration_directory,
|
||||||
const std::string& configuration_basename) {
|
const std::string& configuration_basename) {
|
||||||
#if USE_PROMETHEUS
|
#if USE_PROMETHEUS
|
||||||
metrics::prometheus::FamilyFactory registry;
|
metrics::prometheus::FamilyFactory registry;
|
||||||
cartographer::metrics::RegisterAllMetrics(®istry);
|
::cartographer::metrics::RegisterAllMetrics(®istry);
|
||||||
::prometheus::Exposer exposer("0.0.0.0:9100");
|
::prometheus::Exposer exposer("0.0.0.0:9100");
|
||||||
exposer.RegisterCollectable(registry.GetCollectable());
|
exposer.RegisterCollectable(registry.GetCollectable());
|
||||||
LOG(INFO) << "Exposing metrics at http://localhost:9100/metrics";
|
LOG(INFO) << "Exposing metrics at http://localhost:9100/metrics";
|
||||||
|
@ -52,9 +53,8 @@ void Run(const std::string& configuration_directory,
|
||||||
// config.
|
// config.
|
||||||
map_builder_server_options.mutable_map_builder_options()
|
map_builder_server_options.mutable_map_builder_options()
|
||||||
->set_collate_by_trajectory(true);
|
->set_collate_by_trajectory(true);
|
||||||
auto map_builder =
|
auto map_builder = common::make_unique<mapping::MapBuilder>(
|
||||||
cartographer::common::make_unique<cartographer::mapping::MapBuilder>(
|
map_builder_server_options.map_builder_options());
|
||||||
map_builder_server_options.map_builder_options());
|
|
||||||
std::unique_ptr<MapBuilderServerInterface> map_builder_server =
|
std::unique_ptr<MapBuilderServerInterface> map_builder_server =
|
||||||
CreateMapBuilderServer(map_builder_server_options,
|
CreateMapBuilderServer(map_builder_server_options,
|
||||||
std::move(map_builder));
|
std::move(map_builder));
|
||||||
|
@ -62,7 +62,8 @@ void Run(const std::string& configuration_directory,
|
||||||
map_builder_server->WaitForShutdown();
|
map_builder_server->WaitForShutdown();
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
int main(int argc, char** argv) {
|
int main(int argc, char** argv) {
|
||||||
google::InitGoogleLogging(argv[0]);
|
google::InitGoogleLogging(argv[0]);
|
||||||
|
@ -73,9 +74,9 @@ int main(int argc, char** argv) {
|
||||||
google::ParseCommandLineFlags(&argc, &argv, true);
|
google::ParseCommandLineFlags(&argc, &argv, true);
|
||||||
if (FLAGS_configuration_directory.empty() ||
|
if (FLAGS_configuration_directory.empty() ||
|
||||||
FLAGS_configuration_basename.empty()) {
|
FLAGS_configuration_basename.empty()) {
|
||||||
google::ShowUsageWithFlagsRestrict(argv[0], "cartographer_grpc_server");
|
google::ShowUsageWithFlagsRestrict(argv[0], "cloud_server");
|
||||||
return EXIT_FAILURE;
|
return EXIT_FAILURE;
|
||||||
}
|
}
|
||||||
cartographer_grpc::Run(FLAGS_configuration_directory,
|
cartographer::cloud::Run(FLAGS_configuration_directory,
|
||||||
FLAGS_configuration_basename);
|
FLAGS_configuration_basename);
|
||||||
}
|
}
|
||||||
|
|
|
@ -20,10 +20,11 @@
|
||||||
#include "cartographer/common/make_unique.h"
|
#include "cartographer/common/make_unique.h"
|
||||||
#include "cartographer/mapping/map_builder.h"
|
#include "cartographer/mapping/map_builder.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
proto::MapBuilderServerOptions CreateMapBuilderServerOptions(
|
proto::MapBuilderServerOptions CreateMapBuilderServerOptions(
|
||||||
::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary) {
|
common::LuaParameterDictionary* lua_parameter_dictionary) {
|
||||||
proto::MapBuilderServerOptions map_builder_server_options;
|
proto::MapBuilderServerOptions map_builder_server_options;
|
||||||
map_builder_server_options.set_server_address(
|
map_builder_server_options.set_server_address(
|
||||||
lua_parameter_dictionary->GetString("server_address"));
|
lua_parameter_dictionary->GetString("server_address"));
|
||||||
|
@ -32,7 +33,7 @@ proto::MapBuilderServerOptions CreateMapBuilderServerOptions(
|
||||||
map_builder_server_options.set_num_event_threads(
|
map_builder_server_options.set_num_event_threads(
|
||||||
lua_parameter_dictionary->GetInt("num_event_threads"));
|
lua_parameter_dictionary->GetInt("num_event_threads"));
|
||||||
*map_builder_server_options.mutable_map_builder_options() =
|
*map_builder_server_options.mutable_map_builder_options() =
|
||||||
cartographer::mapping::CreateMapBuilderOptions(
|
mapping::CreateMapBuilderOptions(
|
||||||
lua_parameter_dictionary->GetDictionary("map_builder").get());
|
lua_parameter_dictionary->GetDictionary("map_builder").get());
|
||||||
map_builder_server_options.set_uplink_server_address(
|
map_builder_server_options.set_uplink_server_address(
|
||||||
lua_parameter_dictionary->GetString("uplink_server_address"));
|
lua_parameter_dictionary->GetString("uplink_server_address"));
|
||||||
|
@ -42,14 +43,14 @@ proto::MapBuilderServerOptions CreateMapBuilderServerOptions(
|
||||||
proto::MapBuilderServerOptions LoadMapBuilderServerOptions(
|
proto::MapBuilderServerOptions LoadMapBuilderServerOptions(
|
||||||
const std::string& configuration_directory,
|
const std::string& configuration_directory,
|
||||||
const std::string& configuration_basename) {
|
const std::string& configuration_basename) {
|
||||||
auto file_resolver = cartographer::common::make_unique<
|
auto file_resolver = common::make_unique<common::ConfigurationFileResolver>(
|
||||||
cartographer::common::ConfigurationFileResolver>(
|
|
||||||
std::vector<std::string>{configuration_directory});
|
std::vector<std::string>{configuration_directory});
|
||||||
const std::string code =
|
const std::string code =
|
||||||
file_resolver->GetFileContentOrDie(configuration_basename);
|
file_resolver->GetFileContentOrDie(configuration_basename);
|
||||||
cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
|
common::LuaParameterDictionary lua_parameter_dictionary(
|
||||||
code, std::move(file_resolver));
|
code, std::move(file_resolver));
|
||||||
return CreateMapBuilderServerOptions(&lua_parameter_dictionary);
|
return CreateMapBuilderServerOptions(&lua_parameter_dictionary);
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -22,15 +22,17 @@
|
||||||
#include "cartographer/common/lua_parameter_dictionary.h"
|
#include "cartographer/common/lua_parameter_dictionary.h"
|
||||||
#include "cartographer_grpc/proto/map_builder_server_options.pb.h"
|
#include "cartographer_grpc/proto/map_builder_server_options.pb.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
|
|
||||||
proto::MapBuilderServerOptions CreateMapBuilderServerOptions(
|
proto::MapBuilderServerOptions CreateMapBuilderServerOptions(
|
||||||
::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary);
|
common::LuaParameterDictionary* lua_parameter_dictionary);
|
||||||
|
|
||||||
proto::MapBuilderServerOptions LoadMapBuilderServerOptions(
|
proto::MapBuilderServerOptions LoadMapBuilderServerOptions(
|
||||||
const std::string& configuration_directory,
|
const std::string& configuration_directory,
|
||||||
const std::string& configuration_basename);
|
const std::string& configuration_basename);
|
||||||
|
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_SERVER_OPTIONS_H
|
#endif // CARTOGRAPHER_GRPC_MAP_BUILDER_SERVER_OPTIONS_H
|
||||||
|
|
|
@ -22,15 +22,15 @@
|
||||||
#include "prometheus/gauge.h"
|
#include "prometheus/gauge.h"
|
||||||
#include "prometheus/histogram.h"
|
#include "prometheus/histogram.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace metrics {
|
namespace metrics {
|
||||||
namespace prometheus {
|
namespace prometheus {
|
||||||
|
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
using BucketBoundaries = cartographer::metrics::Histogram::BucketBoundaries;
|
using BucketBoundaries = ::cartographer::metrics::Histogram::BucketBoundaries;
|
||||||
|
|
||||||
class Counter : public cartographer::metrics::Counter {
|
class Counter : public ::cartographer::metrics::Counter {
|
||||||
public:
|
public:
|
||||||
explicit Counter(::prometheus::Counter* prometheus)
|
explicit Counter(::prometheus::Counter* prometheus)
|
||||||
: prometheus_(prometheus) {}
|
: prometheus_(prometheus) {}
|
||||||
|
@ -43,7 +43,7 @@ class Counter : public cartographer::metrics::Counter {
|
||||||
};
|
};
|
||||||
|
|
||||||
class CounterFamily
|
class CounterFamily
|
||||||
: public cartographer::metrics::Family<cartographer::metrics::Counter> {
|
: public ::cartographer::metrics::Family<::cartographer::metrics::Counter> {
|
||||||
public:
|
public:
|
||||||
explicit CounterFamily(
|
explicit CounterFamily(
|
||||||
::prometheus::Family<::prometheus::Counter>* prometheus)
|
::prometheus::Family<::prometheus::Counter>* prometheus)
|
||||||
|
@ -51,7 +51,7 @@ class CounterFamily
|
||||||
|
|
||||||
Counter* Add(const std::map<std::string, std::string>& labels) override {
|
Counter* Add(const std::map<std::string, std::string>& labels) override {
|
||||||
::prometheus::Counter* counter = &prometheus_->Add(labels);
|
::prometheus::Counter* counter = &prometheus_->Add(labels);
|
||||||
auto wrapper = cartographer::common::make_unique<Counter>(counter);
|
auto wrapper = common::make_unique<Counter>(counter);
|
||||||
auto* ptr = wrapper.get();
|
auto* ptr = wrapper.get();
|
||||||
wrappers_.emplace_back(std::move(wrapper));
|
wrappers_.emplace_back(std::move(wrapper));
|
||||||
return ptr;
|
return ptr;
|
||||||
|
@ -62,7 +62,7 @@ class CounterFamily
|
||||||
std::vector<std::unique_ptr<Counter>> wrappers_;
|
std::vector<std::unique_ptr<Counter>> wrappers_;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Gauge : public cartographer::metrics::Gauge {
|
class Gauge : public ::cartographer::metrics::Gauge {
|
||||||
public:
|
public:
|
||||||
explicit Gauge(::prometheus::Gauge* prometheus) : prometheus_(prometheus) {}
|
explicit Gauge(::prometheus::Gauge* prometheus) : prometheus_(prometheus) {}
|
||||||
|
|
||||||
|
@ -77,14 +77,14 @@ class Gauge : public cartographer::metrics::Gauge {
|
||||||
};
|
};
|
||||||
|
|
||||||
class GaugeFamily
|
class GaugeFamily
|
||||||
: public cartographer::metrics::Family<cartographer::metrics::Gauge> {
|
: public ::cartographer::metrics::Family<::cartographer::metrics::Gauge> {
|
||||||
public:
|
public:
|
||||||
explicit GaugeFamily(::prometheus::Family<::prometheus::Gauge>* prometheus)
|
explicit GaugeFamily(::prometheus::Family<::prometheus::Gauge>* prometheus)
|
||||||
: prometheus_(prometheus) {}
|
: prometheus_(prometheus) {}
|
||||||
|
|
||||||
Gauge* Add(const std::map<std::string, std::string>& labels) override {
|
Gauge* Add(const std::map<std::string, std::string>& labels) override {
|
||||||
::prometheus::Gauge* gauge = &prometheus_->Add(labels);
|
::prometheus::Gauge* gauge = &prometheus_->Add(labels);
|
||||||
auto wrapper = cartographer::common::make_unique<Gauge>(gauge);
|
auto wrapper = common::make_unique<Gauge>(gauge);
|
||||||
auto* ptr = wrapper.get();
|
auto* ptr = wrapper.get();
|
||||||
wrappers_.emplace_back(std::move(wrapper));
|
wrappers_.emplace_back(std::move(wrapper));
|
||||||
return ptr;
|
return ptr;
|
||||||
|
@ -95,7 +95,7 @@ class GaugeFamily
|
||||||
std::vector<std::unique_ptr<Gauge>> wrappers_;
|
std::vector<std::unique_ptr<Gauge>> wrappers_;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Histogram : public cartographer::metrics::Histogram {
|
class Histogram : public ::cartographer::metrics::Histogram {
|
||||||
public:
|
public:
|
||||||
explicit Histogram(::prometheus::Histogram* prometheus)
|
explicit Histogram(::prometheus::Histogram* prometheus)
|
||||||
: prometheus_(prometheus) {}
|
: prometheus_(prometheus) {}
|
||||||
|
@ -106,8 +106,8 @@ class Histogram : public cartographer::metrics::Histogram {
|
||||||
::prometheus::Histogram* prometheus_;
|
::prometheus::Histogram* prometheus_;
|
||||||
};
|
};
|
||||||
|
|
||||||
class HistogramFamily
|
class HistogramFamily : public ::cartographer::metrics::Family<
|
||||||
: public cartographer::metrics::Family<cartographer::metrics::Histogram> {
|
::cartographer::metrics::Histogram> {
|
||||||
public:
|
public:
|
||||||
HistogramFamily(::prometheus::Family<::prometheus::Histogram>* prometheus,
|
HistogramFamily(::prometheus::Family<::prometheus::Histogram>* prometheus,
|
||||||
const BucketBoundaries& boundaries)
|
const BucketBoundaries& boundaries)
|
||||||
|
@ -115,7 +115,7 @@ class HistogramFamily
|
||||||
|
|
||||||
Histogram* Add(const std::map<std::string, std::string>& labels) override {
|
Histogram* Add(const std::map<std::string, std::string>& labels) override {
|
||||||
::prometheus::Histogram* histogram = &prometheus_->Add(labels, boundaries_);
|
::prometheus::Histogram* histogram = &prometheus_->Add(labels, boundaries_);
|
||||||
auto wrapper = cartographer::common::make_unique<Histogram>(histogram);
|
auto wrapper = common::make_unique<Histogram>(histogram);
|
||||||
auto* ptr = wrapper.get();
|
auto* ptr = wrapper.get();
|
||||||
wrappers_.emplace_back(std::move(wrapper));
|
wrappers_.emplace_back(std::move(wrapper));
|
||||||
return ptr;
|
return ptr;
|
||||||
|
@ -132,33 +132,33 @@ class HistogramFamily
|
||||||
FamilyFactory::FamilyFactory()
|
FamilyFactory::FamilyFactory()
|
||||||
: registry_(std::make_shared<::prometheus::Registry>()) {}
|
: registry_(std::make_shared<::prometheus::Registry>()) {}
|
||||||
|
|
||||||
cartographer::metrics::Family<cartographer::metrics::Counter>*
|
::cartographer::metrics::Family<::cartographer::metrics::Counter>*
|
||||||
FamilyFactory::NewCounterFamily(const std::string& name,
|
FamilyFactory::NewCounterFamily(const std::string& name,
|
||||||
const std::string& description) {
|
const std::string& description) {
|
||||||
auto& family = ::prometheus::BuildCounter()
|
auto& family = ::prometheus::BuildCounter()
|
||||||
.Name(name)
|
.Name(name)
|
||||||
.Help(description)
|
.Help(description)
|
||||||
.Register(*registry_);
|
.Register(*registry_);
|
||||||
auto wrapper = cartographer::common::make_unique<CounterFamily>(&family);
|
auto wrapper = common::make_unique<CounterFamily>(&family);
|
||||||
auto* ptr = wrapper.get();
|
auto* ptr = wrapper.get();
|
||||||
counters_.emplace_back(std::move(wrapper));
|
counters_.emplace_back(std::move(wrapper));
|
||||||
return ptr;
|
return ptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::metrics::Family<cartographer::metrics::Gauge>*
|
::cartographer::metrics::Family<::cartographer::metrics::Gauge>*
|
||||||
FamilyFactory::NewGaugeFamily(const std::string& name,
|
FamilyFactory::NewGaugeFamily(const std::string& name,
|
||||||
const std::string& description) {
|
const std::string& description) {
|
||||||
auto& family = ::prometheus::BuildGauge()
|
auto& family = ::prometheus::BuildGauge()
|
||||||
.Name(name)
|
.Name(name)
|
||||||
.Help(description)
|
.Help(description)
|
||||||
.Register(*registry_);
|
.Register(*registry_);
|
||||||
auto wrapper = cartographer::common::make_unique<GaugeFamily>(&family);
|
auto wrapper = common::make_unique<GaugeFamily>(&family);
|
||||||
auto* ptr = wrapper.get();
|
auto* ptr = wrapper.get();
|
||||||
gauges_.emplace_back(std::move(wrapper));
|
gauges_.emplace_back(std::move(wrapper));
|
||||||
return ptr;
|
return ptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
cartographer::metrics::Family<cartographer::metrics::Histogram>*
|
::cartographer::metrics::Family<::cartographer::metrics::Histogram>*
|
||||||
FamilyFactory::NewHistogramFamily(const std::string& name,
|
FamilyFactory::NewHistogramFamily(const std::string& name,
|
||||||
const std::string& description,
|
const std::string& description,
|
||||||
const BucketBoundaries& boundaries) {
|
const BucketBoundaries& boundaries) {
|
||||||
|
@ -166,8 +166,7 @@ FamilyFactory::NewHistogramFamily(const std::string& name,
|
||||||
.Name(name)
|
.Name(name)
|
||||||
.Help(description)
|
.Help(description)
|
||||||
.Register(*registry_);
|
.Register(*registry_);
|
||||||
auto wrapper =
|
auto wrapper = common::make_unique<HistogramFamily>(&family, boundaries);
|
||||||
cartographer::common::make_unique<HistogramFamily>(&family, boundaries);
|
|
||||||
auto* ptr = wrapper.get();
|
auto* ptr = wrapper.get();
|
||||||
histograms_.emplace_back(std::move(wrapper));
|
histograms_.emplace_back(std::move(wrapper));
|
||||||
return ptr;
|
return ptr;
|
||||||
|
@ -179,4 +178,5 @@ std::weak_ptr<::prometheus::Collectable> FamilyFactory::GetCollectable() const {
|
||||||
|
|
||||||
} // namespace prometheus
|
} // namespace prometheus
|
||||||
} // namespace metrics
|
} // namespace metrics
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -23,41 +23,44 @@
|
||||||
#include "cartographer/metrics/family_factory.h"
|
#include "cartographer/metrics/family_factory.h"
|
||||||
#include "prometheus/registry.h"
|
#include "prometheus/registry.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace metrics {
|
namespace metrics {
|
||||||
namespace prometheus {
|
namespace prometheus {
|
||||||
|
|
||||||
class FamilyFactory : public cartographer::metrics::FamilyFactory {
|
class FamilyFactory : public ::cartographer::metrics::FamilyFactory {
|
||||||
public:
|
public:
|
||||||
FamilyFactory();
|
FamilyFactory();
|
||||||
|
|
||||||
cartographer::metrics::Family<cartographer::metrics::Counter>*
|
::cartographer::metrics::Family<::cartographer::metrics::Counter>*
|
||||||
NewCounterFamily(const std::string& name,
|
NewCounterFamily(const std::string& name,
|
||||||
const std::string& description) override;
|
const std::string& description) override;
|
||||||
cartographer::metrics::Family<cartographer::metrics::Gauge>* NewGaugeFamily(
|
::cartographer::metrics::Family<::cartographer::metrics::Gauge>*
|
||||||
const std::string& name, const std::string& description) override;
|
NewGaugeFamily(const std::string& name,
|
||||||
cartographer::metrics::Family<cartographer::metrics::Histogram>*
|
const std::string& description) override;
|
||||||
|
::cartographer::metrics::Family<::cartographer::metrics::Histogram>*
|
||||||
NewHistogramFamily(const std::string& name, const std::string& description,
|
NewHistogramFamily(const std::string& name, const std::string& description,
|
||||||
const cartographer::metrics::Histogram::BucketBoundaries&
|
const ::cartographer::metrics::Histogram::BucketBoundaries&
|
||||||
boundaries) override;
|
boundaries) override;
|
||||||
|
|
||||||
std::weak_ptr<::prometheus::Collectable> GetCollectable() const;
|
std::weak_ptr<::prometheus::Collectable> GetCollectable() const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
std::vector<std::unique_ptr<
|
std::vector<std::unique_ptr<
|
||||||
cartographer::metrics::Family<cartographer::metrics::Counter>>>
|
::cartographer::metrics::Family<::cartographer::metrics::Counter>>>
|
||||||
counters_;
|
counters_;
|
||||||
std::vector<std::unique_ptr<
|
std::vector<std::unique_ptr<
|
||||||
cartographer::metrics::Family<cartographer::metrics::Gauge>>>
|
::cartographer::metrics::Family<::cartographer::metrics::Gauge>>>
|
||||||
gauges_;
|
gauges_;
|
||||||
std::vector<std::unique_ptr<
|
std::vector<std::unique_ptr<
|
||||||
cartographer::metrics::Family<cartographer::metrics::Histogram>>>
|
::cartographer::metrics::Family<::cartographer::metrics::Histogram>>>
|
||||||
histograms_;
|
histograms_;
|
||||||
std::shared_ptr<::prometheus::Registry> registry_;
|
std::shared_ptr<::prometheus::Registry> registry_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace prometheus
|
} // namespace prometheus
|
||||||
} // namespace metrics
|
} // namespace metrics
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_GRPC_METRICS_PROMETHEUS_FAMILY_FACTORY_H_
|
#endif // CARTOGRAPHER_GRPC_METRICS_PROMETHEUS_FAMILY_FACTORY_H_
|
||||||
|
|
|
@ -22,14 +22,15 @@
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
#include "prometheus/exposer.h"
|
#include "prometheus/exposer.h"
|
||||||
|
|
||||||
namespace cartographer_grpc {
|
namespace cartographer {
|
||||||
|
namespace cloud {
|
||||||
namespace metrics {
|
namespace metrics {
|
||||||
namespace prometheus {
|
namespace prometheus {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
static auto* kCounter = cartographer::metrics::Counter::Null();
|
static auto* kCounter = ::cartographer::metrics::Counter::Null();
|
||||||
static auto* kGauge = cartographer::metrics::Gauge::Null();
|
static auto* kGauge = ::cartographer::metrics::Gauge::Null();
|
||||||
static auto* kScoresMetric = cartographer::metrics::Histogram::Null();
|
static auto* kScoresMetric = ::cartographer::metrics::Histogram::Null();
|
||||||
|
|
||||||
const char kLabelKey[] = "kind";
|
const char kLabelKey[] = "kind";
|
||||||
const char kLabelValue[] = "score";
|
const char kLabelValue[] = "score";
|
||||||
|
@ -37,8 +38,8 @@ const std::array<double, 5> kObserveScores = {{-1, 0.11, 0.2, 0.5, 2}};
|
||||||
|
|
||||||
class Algorithm {
|
class Algorithm {
|
||||||
public:
|
public:
|
||||||
static void RegisterMetrics(cartographer::metrics::FamilyFactory* factory) {
|
static void RegisterMetrics(::cartographer::metrics::FamilyFactory* factory) {
|
||||||
auto boundaries = cartographer::metrics::Histogram::FixedWidth(0.05, 20);
|
auto boundaries = ::cartographer::metrics::Histogram::FixedWidth(0.05, 20);
|
||||||
auto* scores_family = factory->NewHistogramFamily(
|
auto* scores_family = factory->NewHistogramFamily(
|
||||||
"/algorithm/scores", "Scores achieved", boundaries);
|
"/algorithm/scores", "Scores achieved", boundaries);
|
||||||
kScoresMetric = scores_family->Add({{kLabelKey, kLabelValue}});
|
kScoresMetric = scores_family->Add({{kLabelKey, kLabelValue}});
|
||||||
|
@ -134,7 +135,7 @@ TEST(MetricsTest, CollectHistogram) {
|
||||||
TEST(MetricsTest, RunExposerServer) {
|
TEST(MetricsTest, RunExposerServer) {
|
||||||
FamilyFactory registry;
|
FamilyFactory registry;
|
||||||
Algorithm::RegisterMetrics(®istry);
|
Algorithm::RegisterMetrics(®istry);
|
||||||
cartographer::metrics::RegisterAllMetrics(®istry);
|
::cartographer::metrics::RegisterAllMetrics(®istry);
|
||||||
::prometheus::Exposer exposer("0.0.0.0:9100");
|
::prometheus::Exposer exposer("0.0.0.0:9100");
|
||||||
exposer.RegisterCollectable(registry.GetCollectable());
|
exposer.RegisterCollectable(registry.GetCollectable());
|
||||||
|
|
||||||
|
@ -145,4 +146,5 @@ TEST(MetricsTest, RunExposerServer) {
|
||||||
} // namespace
|
} // namespace
|
||||||
} // namespace prometheus
|
} // namespace prometheus
|
||||||
} // namespace metrics
|
} // namespace metrics
|
||||||
} // namespace cartographer_grpc
|
} // namespace cloud
|
||||||
|
} // namespace cartographer
|
||||||
|
|
|
@ -16,7 +16,7 @@ syntax = "proto3";
|
||||||
|
|
||||||
import "cartographer/mapping/proto/map_builder_options.proto";
|
import "cartographer/mapping/proto/map_builder_options.proto";
|
||||||
|
|
||||||
package cartographer_grpc.proto;
|
package cartographer.cloud.proto;
|
||||||
|
|
||||||
message MapBuilderServerOptions {
|
message MapBuilderServerOptions {
|
||||||
string server_address = 1;
|
string server_address = 1;
|
||||||
|
|
|
@ -22,7 +22,7 @@ import "cartographer/sensor/proto/sensor.proto";
|
||||||
import "cartographer/transform/proto/transform.proto";
|
import "cartographer/transform/proto/transform.proto";
|
||||||
import "google/protobuf/empty.proto";
|
import "google/protobuf/empty.proto";
|
||||||
|
|
||||||
package cartographer_grpc.proto;
|
package cartographer.cloud.proto;
|
||||||
|
|
||||||
enum SensorType {
|
enum SensorType {
|
||||||
RANGE = 0;
|
RANGE = 0;
|
||||||
|
|
Loading…
Reference in New Issue