NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
pose_with_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_WITH_COVARIANCE_INTERPOLATER_H_
20 #define LOCALIZATION_COMMON_POSE_WITH_COVARIANCE_INTERPOLATER_H_
21 
25 
26 namespace localization_common {
28  PoseWithCovarianceInterpolaterParams(const std::shared_ptr<PoseCovarianceInterpolater>& pose_covariance_interpolater =
29  std::make_shared<PoseCovarianceInterpolater>())
31  std::shared_ptr<PoseCovarianceInterpolater> pose_covariance_interpolater;
32 };
33 
36 
37 template <>
39  const double alpha) const;
40 
41 template <>
42 boost::optional<PoseWithCovariance> PoseWithCovarianceInterpolater::Relative(const Time timestamp_a,
43  const Time timestamp_b) const;
44 } // namespace localization_common
45 
46 #endif // LOCALIZATION_COMMON_POSE_WITH_COVARIANCE_INTERPOLATER_H_
localization_common
Definition: averager.h:33
localization_common::TimestampedInterpolater::Interpolate
boost::optional< T > Interpolate(const Time timestamp) const
Definition: timestamped_interpolater.h:87
localization_common::PoseWithCovarianceInterpolaterParams::pose_covariance_interpolater
std::shared_ptr< PoseCovarianceInterpolater > pose_covariance_interpolater
Definition: pose_with_covariance_interpolater.h:31
pose_covariance_interpolater.h
pose_with_covariance.h
localization_common::TimestampedInterpolater::Relative
boost::optional< T > Relative(const Time timestamp_a, const Time timestamp_b) const
Definition: timestamped_interpolater.h:109
localization_common::PoseWithCovariance
Definition: pose_with_covariance.h:28
localization_common::TimestampedInterpolater
Definition: timestamped_interpolater.h:40
timestamped_interpolater.h
localization_common::Time
double Time
Definition: time.h:23
localization_common::PoseWithCovarianceInterpolaterParams
Definition: pose_with_covariance_interpolater.h:27
localization_common::PoseWithCovarianceInterpolaterParams::PoseWithCovarianceInterpolaterParams
PoseWithCovarianceInterpolaterParams(const std::shared_ptr< PoseCovarianceInterpolater > &pose_covariance_interpolater=std::make_shared< PoseCovarianceInterpolater >())
Definition: pose_with_covariance_interpolater.h:28