probability_values.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_MAPPING_PROBABILITY_VALUES_H_
00018 #define CARTOGRAPHER_MAPPING_PROBABILITY_VALUES_H_
00019 
00020 #include <cmath>
00021 #include <vector>
00022 
00023 #include "cartographer/common/math.h"
00024 #include "cartographer/common/port.h"
00025 #include "glog/logging.h"
00026 
00027 namespace cartographer {
00028 namespace mapping {
00029 
00030 namespace {
00031 
00032 inline uint16 BoundedFloatToValue(const float float_value,
00033                                   const float lower_bound,
00034                                   const float upper_bound) {
00035   const int value =
00036       common::RoundToInt(
00037           (common::Clamp(float_value, lower_bound, upper_bound) - lower_bound) *
00038           (32766.f / (upper_bound - lower_bound))) +
00039       1;
00040   // DCHECK for performance.
00041   DCHECK_GE(value, 1);
00042   DCHECK_LE(value, 32767);
00043   return value;
00044 }
00045 
00046 }  // namespace
00047 
00048 inline float Odds(float probability) {
00049   return probability / (1.f - probability);
00050 }
00051 
00052 inline float ProbabilityFromOdds(const float odds) {
00053   return odds / (odds + 1.f);
00054 }
00055 
00056 inline float ProbabilityToCorrespondenceCost(const float probability) {
00057   return 1.f - probability;
00058 }
00059 
00060 inline float CorrespondenceCostToProbability(const float correspondence_cost) {
00061   return 1.f - correspondence_cost;
00062 }
00063 
00064 constexpr float kMinProbability = 0.1f;
00065 constexpr float kMaxProbability = 1.f - kMinProbability;
00066 constexpr float kMinCorrespondenceCost = 1.f - kMaxProbability;
00067 constexpr float kMaxCorrespondenceCost = 1.f - kMinProbability;
00068 
00069 // Clamps probability to be in the range [kMinProbability, kMaxProbability].
00070 inline float ClampProbability(const float probability) {
00071   return common::Clamp(probability, kMinProbability, kMaxProbability);
00072 }
00073 // Clamps correspondece cost to be in the range [kMinCorrespondenceCost,
00074 // kMaxCorrespondenceCost].
00075 inline float ClampCorrespondenceCost(const float correspondence_cost) {
00076   return common::Clamp(correspondence_cost, kMinCorrespondenceCost,
00077                        kMaxCorrespondenceCost);
00078 }
00079 
00080 constexpr uint16 kUnknownProbabilityValue = 0;
00081 constexpr uint16 kUnknownCorrespondenceValue = kUnknownProbabilityValue;
00082 constexpr uint16 kUpdateMarker = 1u << 15;
00083 
00084 // Converts a correspondence_cost to a uint16 in the [1, 32767] range.
00085 inline uint16 CorrespondenceCostToValue(const float correspondence_cost) {
00086   return BoundedFloatToValue(correspondence_cost, kMinCorrespondenceCost,
00087                              kMaxCorrespondenceCost);
00088 }
00089 
00090 // Converts a probability to a uint16 in the [1, 32767] range.
00091 inline uint16 ProbabilityToValue(const float probability) {
00092   return BoundedFloatToValue(probability, kMinProbability, kMaxProbability);
00093 }
00094 
00095 extern const std::vector<float>* const kValueToProbability;
00096 extern const std::vector<float>* const kValueToCorrespondenceCost;
00097 
00098 // Converts a uint16 (which may or may not have the update marker set) to a
00099 // probability in the range [kMinProbability, kMaxProbability].
00100 inline float ValueToProbability(const uint16 value) {
00101   return (*kValueToProbability)[value];
00102 }
00103 
00104 // Converts a uint16 (which may or may not have the update marker set) to a
00105 // correspondence cost in the range [kMinCorrespondenceCost,
00106 // kMaxCorrespondenceCost].
00107 inline float ValueToCorrespondenceCost(const uint16 value) {
00108   return (*kValueToCorrespondenceCost)[value];
00109 }
00110 
00111 inline uint16 ProbabilityValueToCorrespondenceCostValue(
00112     uint16 probability_value) {
00113   if (probability_value == kUnknownProbabilityValue) {
00114     return kUnknownCorrespondenceValue;
00115   }
00116   bool update_carry = false;
00117   if (probability_value > kUpdateMarker) {
00118     probability_value -= kUpdateMarker;
00119     update_carry = true;
00120   }
00121   uint16 result = CorrespondenceCostToValue(
00122       ProbabilityToCorrespondenceCost(ValueToProbability(probability_value)));
00123   if (update_carry) result += kUpdateMarker;
00124   return result;
00125 }
00126 
00127 inline uint16 CorrespondenceCostValueToProbabilityValue(
00128     uint16 correspondence_cost_value) {
00129   if (correspondence_cost_value == kUnknownCorrespondenceValue)
00130     return kUnknownProbabilityValue;
00131   bool update_carry = false;
00132   if (correspondence_cost_value > kUpdateMarker) {
00133     correspondence_cost_value -= kUpdateMarker;
00134     update_carry = true;
00135   }
00136   uint16 result = ProbabilityToValue(CorrespondenceCostToProbability(
00137       ValueToCorrespondenceCost(correspondence_cost_value)));
00138   if (update_carry) result += kUpdateMarker;
00139   return result;
00140 }
00141 
00142 std::vector<uint16> ComputeLookupTableToApplyOdds(float odds);
00143 std::vector<uint16> ComputeLookupTableToApplyCorrespondenceCostOdds(float odds);
00144 
00145 }  // namespace mapping
00146 }  // namespace cartographer
00147 
00148 #endif  // CARTOGRAPHER_MAPPING_PROBABILITY_VALUES_H_


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35