Use LocalSlamResultCallback for trajectory states (#594)
Replaces #556. Use `LocalSlamResultCallback` googlecartographer/cartographer#574 instead of `PoseEstimate`.master
parent
a10dea9c11
commit
fd52ddf45b
|
@ -65,7 +65,26 @@ void PushAndResetLineMarker(visualization_msgs::Marker* marker,
|
||||||
MapBuilderBridge::MapBuilderBridge(const NodeOptions& node_options,
|
MapBuilderBridge::MapBuilderBridge(const NodeOptions& node_options,
|
||||||
tf2_ros::Buffer* const tf_buffer)
|
tf2_ros::Buffer* const tf_buffer)
|
||||||
: node_options_(node_options),
|
: node_options_(node_options),
|
||||||
map_builder_(node_options.map_builder_options, {}),
|
map_builder_(
|
||||||
|
node_options.map_builder_options,
|
||||||
|
cartographer::mapping::MapBuilder::LocalSlamResultCallback(
|
||||||
|
[this](
|
||||||
|
const int trajectory_id,
|
||||||
|
const ::cartographer::common::Time time,
|
||||||
|
const ::cartographer::transform::Rigid3d local_pose,
|
||||||
|
::cartographer::sensor::RangeData range_data_in_local,
|
||||||
|
const std::unique_ptr<const ::cartographer::mapping::NodeId>)
|
||||||
|
EXCLUDES(mutex_) {
|
||||||
|
std::shared_ptr<const TrajectoryState::LocalSlamData>
|
||||||
|
local_slam_data =
|
||||||
|
std::make_shared<TrajectoryState::LocalSlamData>(
|
||||||
|
TrajectoryState::LocalSlamData{
|
||||||
|
time, local_pose,
|
||||||
|
std::move(range_data_in_local)});
|
||||||
|
cartographer::common::MutexLocker lock(&mutex_);
|
||||||
|
trajectory_state_data_[trajectory_id] =
|
||||||
|
std::move(local_slam_data);
|
||||||
|
})),
|
||||||
tf_buffer_(tf_buffer) {}
|
tf_buffer_(tf_buffer) {}
|
||||||
|
|
||||||
void MapBuilderBridge::LoadMap(const std::string& map_filename) {
|
void MapBuilderBridge::LoadMap(const std::string& map_filename) {
|
||||||
|
@ -169,24 +188,22 @@ MapBuilderBridge::GetTrajectoryStates() {
|
||||||
const int trajectory_id = entry.first;
|
const int trajectory_id = entry.first;
|
||||||
const SensorBridge& sensor_bridge = *entry.second;
|
const SensorBridge& sensor_bridge = *entry.second;
|
||||||
|
|
||||||
const cartographer::mapping::TrajectoryBuilder* const trajectory_builder =
|
std::shared_ptr<const TrajectoryState::LocalSlamData> local_slam_data;
|
||||||
map_builder_.GetTrajectoryBuilder(trajectory_id);
|
{
|
||||||
if (trajectory_builder == nullptr) {
|
cartographer::common::MutexLocker lock(&mutex_);
|
||||||
continue;
|
if (trajectory_state_data_.count(trajectory_id) == 0) {
|
||||||
}
|
continue;
|
||||||
const cartographer::mapping::TrajectoryBuilder::PoseEstimate pose_estimate =
|
}
|
||||||
trajectory_builder->pose_estimate();
|
local_slam_data = trajectory_state_data_.at(trajectory_id);
|
||||||
if (cartographer::common::ToUniversal(pose_estimate.time) < 0) {
|
|
||||||
continue;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Make sure there is a trajectory with 'trajectory_id'.
|
// Make sure there is a trajectory with 'trajectory_id'.
|
||||||
CHECK_EQ(trajectory_options_.count(trajectory_id), 1);
|
CHECK_EQ(trajectory_options_.count(trajectory_id), 1);
|
||||||
trajectory_states[trajectory_id] = {
|
trajectory_states[trajectory_id] = {
|
||||||
pose_estimate,
|
local_slam_data,
|
||||||
map_builder_.pose_graph()->GetLocalToGlobalTransform(trajectory_id),
|
map_builder_.pose_graph()->GetLocalToGlobalTransform(trajectory_id),
|
||||||
sensor_bridge.tf_bridge().LookupToTracking(
|
sensor_bridge.tf_bridge().LookupToTracking(
|
||||||
pose_estimate.time,
|
local_slam_data->time,
|
||||||
trajectory_options_[trajectory_id].published_frame),
|
trajectory_options_[trajectory_id].published_frame),
|
||||||
trajectory_options_[trajectory_id]};
|
trajectory_options_[trajectory_id]};
|
||||||
}
|
}
|
||||||
|
|
|
@ -39,7 +39,15 @@ namespace cartographer_ros {
|
||||||
class MapBuilderBridge {
|
class MapBuilderBridge {
|
||||||
public:
|
public:
|
||||||
struct TrajectoryState {
|
struct TrajectoryState {
|
||||||
cartographer::mapping::TrajectoryBuilder::PoseEstimate pose_estimate;
|
// Contains the trajectory state data received from local SLAM, after
|
||||||
|
// it had processed accumulated 'range_data_in_local' and estimated
|
||||||
|
// current 'local_pose' at 'time'.
|
||||||
|
struct LocalSlamData {
|
||||||
|
::cartographer::common::Time time;
|
||||||
|
::cartographer::transform::Rigid3d local_pose;
|
||||||
|
::cartographer::sensor::RangeData range_data_in_local;
|
||||||
|
};
|
||||||
|
std::shared_ptr<const LocalSlamData> local_slam_data;
|
||||||
cartographer::transform::Rigid3d local_to_map;
|
cartographer::transform::Rigid3d local_to_map;
|
||||||
std::unique_ptr<cartographer::transform::Rigid3d> published_to_tracking;
|
std::unique_ptr<cartographer::transform::Rigid3d> published_to_tracking;
|
||||||
TrajectoryOptions trajectory_options;
|
TrajectoryOptions trajectory_options;
|
||||||
|
@ -62,14 +70,18 @@ class MapBuilderBridge {
|
||||||
cartographer_ros_msgs::SubmapQuery::Response& response);
|
cartographer_ros_msgs::SubmapQuery::Response& response);
|
||||||
|
|
||||||
cartographer_ros_msgs::SubmapList GetSubmapList();
|
cartographer_ros_msgs::SubmapList GetSubmapList();
|
||||||
std::unordered_map<int, TrajectoryState> GetTrajectoryStates();
|
std::unordered_map<int, TrajectoryState> GetTrajectoryStates()
|
||||||
|
EXCLUDES(mutex_);
|
||||||
visualization_msgs::MarkerArray GetTrajectoryNodeList();
|
visualization_msgs::MarkerArray GetTrajectoryNodeList();
|
||||||
visualization_msgs::MarkerArray GetConstraintList();
|
visualization_msgs::MarkerArray GetConstraintList();
|
||||||
|
|
||||||
SensorBridge* sensor_bridge(int trajectory_id);
|
SensorBridge* sensor_bridge(int trajectory_id);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
cartographer::common::Mutex mutex_;
|
||||||
const NodeOptions node_options_;
|
const NodeOptions node_options_;
|
||||||
|
std::unordered_map<int, std::shared_ptr<const TrajectoryState::LocalSlamData>>
|
||||||
|
trajectory_state_data_ GUARDED_BY(mutex_);
|
||||||
cartographer::mapping::MapBuilder map_builder_;
|
cartographer::mapping::MapBuilder map_builder_;
|
||||||
tf2_ros::Buffer* const tf_buffer_;
|
tf2_ros::Buffer* const tf_buffer_;
|
||||||
|
|
||||||
|
|
|
@ -169,23 +169,25 @@ void Node::PublishTrajectoryStates(const ::ros::WallTimerEvent& timer_event) {
|
||||||
auto& extrapolator = extrapolators_.at(entry.first);
|
auto& extrapolator = extrapolators_.at(entry.first);
|
||||||
// We only publish a point cloud if it has changed. It is not needed at high
|
// We only publish a point cloud if it has changed. It is not needed at high
|
||||||
// frequency, and republishing it would be computationally wasteful.
|
// frequency, and republishing it would be computationally wasteful.
|
||||||
if (trajectory_state.pose_estimate.time != extrapolator.GetLastPoseTime()) {
|
if (trajectory_state.local_slam_data->time !=
|
||||||
|
extrapolator.GetLastPoseTime()) {
|
||||||
// TODO(gaschler): Consider using other message without time information.
|
// TODO(gaschler): Consider using other message without time information.
|
||||||
carto::sensor::TimedPointCloud point_cloud;
|
carto::sensor::TimedPointCloud point_cloud;
|
||||||
point_cloud.reserve(trajectory_state.pose_estimate.point_cloud.size());
|
point_cloud.reserve(
|
||||||
|
trajectory_state.local_slam_data->range_data_in_local.returns.size());
|
||||||
for (const Eigen::Vector3f point :
|
for (const Eigen::Vector3f point :
|
||||||
trajectory_state.pose_estimate.point_cloud) {
|
trajectory_state.local_slam_data->range_data_in_local.returns) {
|
||||||
Eigen::Vector4f point_time;
|
Eigen::Vector4f point_time;
|
||||||
point_time << point, 0.f;
|
point_time << point, 0.f;
|
||||||
point_cloud.push_back(point_time);
|
point_cloud.push_back(point_time);
|
||||||
}
|
}
|
||||||
scan_matched_point_cloud_publisher_.publish(ToPointCloud2Message(
|
scan_matched_point_cloud_publisher_.publish(ToPointCloud2Message(
|
||||||
carto::common::ToUniversal(trajectory_state.pose_estimate.time),
|
carto::common::ToUniversal(trajectory_state.local_slam_data->time),
|
||||||
node_options_.map_frame,
|
node_options_.map_frame,
|
||||||
carto::sensor::TransformTimedPointCloud(
|
carto::sensor::TransformTimedPointCloud(
|
||||||
point_cloud, trajectory_state.local_to_map.cast<float>())));
|
point_cloud, trajectory_state.local_to_map.cast<float>())));
|
||||||
extrapolator.AddPose(trajectory_state.pose_estimate.time,
|
extrapolator.AddPose(trajectory_state.local_slam_data->time,
|
||||||
trajectory_state.pose_estimate.pose);
|
trajectory_state.local_slam_data->local_pose);
|
||||||
}
|
}
|
||||||
|
|
||||||
geometry_msgs::TransformStamped stamped_transform;
|
geometry_msgs::TransformStamped stamped_transform;
|
||||||
|
|
Loading…
Reference in New Issue