NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
pose_covariance_interpolater.h
Go to the documentation of this file.
1
/* Copyright (c) 2017, United States Government, as represented by the
2
* Administrator of the National Aeronautics and Space Administration.
3
*
4
* All rights reserved.
5
*
6
* The Astrobee platform is licensed under the Apache License, Version 2.0
7
* (the "License"); you may not use this file except in compliance with the
8
* License. You may obtain a copy of the License at
9
*
10
* http://www.apache.org/licenses/LICENSE-2.0
11
*
12
* Unless required by applicable law or agreed to in writing, software
13
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15
* License for the specific language governing permissions and limitations
16
* under the License.
17
*/
18
19
#ifndef LOCALIZATION_COMMON_POSE_COVARIANCE_INTERPOLATER_H_
20
#define LOCALIZATION_COMMON_POSE_COVARIANCE_INTERPOLATER_H_
21
22
#include <
localization_common/pose_with_covariance.h
>
23
24
namespace
localization_common
{
25
class
PoseCovarianceInterpolater
{
26
public
:
27
PoseCovarianceInterpolater
() =
default
;
28
virtual
~PoseCovarianceInterpolater
() =
default
;
29
virtual
PoseCovariance
Interpolate
(
const
PoseWithCovariance
& a,
const
PoseWithCovariance
& b,
const
Time
& timestamp_a,
30
const
Time
& timestamp_b);
31
};
32
}
// namespace localization_common
33
34
#endif // LOCALIZATION_COMMON_POSE_COVARIANCE_INTERPOLATER_H_
localization_common
Definition:
averager.h:33
pose_with_covariance.h
localization_common::PoseCovarianceInterpolater::Interpolate
virtual PoseCovariance Interpolate(const PoseWithCovariance &a, const PoseWithCovariance &b, const Time ×tamp_a, const Time ×tamp_b)
Definition:
pose_covariance_interpolater.cc:23
localization_common::PoseCovarianceInterpolater::~PoseCovarianceInterpolater
virtual ~PoseCovarianceInterpolater()=default
localization_common::PoseCovariance
Eigen::Matrix< double, 6, 6 > PoseCovariance
Definition:
pose_with_covariance.h:27
localization_common::PoseWithCovariance
Definition:
pose_with_covariance.h:28
localization_common::PoseCovarianceInterpolater::PoseCovarianceInterpolater
PoseCovarianceInterpolater()=default
localization_common::PoseCovarianceInterpolater
Definition:
pose_covariance_interpolater.h:25
localization_common::Time
double Time
Definition:
time.h:23