gtsam  4.1.0
gtsam
SmartFactorBase.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
21 #pragma once
22 
23 #include <gtsam/slam/JacobianFactorQ.h>
24 #include <gtsam/slam/JacobianFactorSVD.h>
26 
30 
31 #include <boost/optional.hpp>
32 #include <boost/serialization/optional.hpp>
33 #include <boost/make_shared.hpp>
34 #include <vector>
35 
36 namespace gtsam {
37 
46 template<class CAMERA>
48 
49 private:
50  typedef NonlinearFactor Base;
52  typedef typename CAMERA::Measurement Z;
53  typedef typename CAMERA::MeasurementVector ZVector;
54 
55 public:
56 
57  static const int Dim = traits<CAMERA>::dimension;
58  static const int ZDim = traits<Z>::dimension;
59  typedef Eigen::Matrix<double, ZDim, Dim> MatrixZD; // F blocks (derivatives wrpt camera)
60  typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks; // vector of F blocks
61 
62 protected:
69  SharedIsotropic noiseModel_;
70 
76  ZVector measured_;
77 
78  boost::optional<Pose3> body_P_sensor_;
79 
80  // Cache for Fblocks, to avoid a malloc ever time we re-linearize
81  mutable FBlocks Fs;
82 
83  public:
85 
87  typedef boost::shared_ptr<This> shared_ptr;
88 
91 
94 
96  SmartFactorBase(const SharedNoiseModel& sharedNoiseModel,
97  boost::optional<Pose3> body_P_sensor = boost::none,
98  size_t expectedNumberCameras = 10)
99  : body_P_sensor_(body_P_sensor), Fs(expectedNumberCameras) {
100 
101  if (!sharedNoiseModel)
102  throw std::runtime_error("SmartFactorBase: sharedNoiseModel is required");
103 
104  SharedIsotropic sharedIsotropic = boost::dynamic_pointer_cast<
105  noiseModel::Isotropic>(sharedNoiseModel);
106 
107  if (!sharedIsotropic)
108  throw std::runtime_error("SmartFactorBase: needs isotropic");
109 
110  noiseModel_ = sharedIsotropic;
111  }
112 
114  virtual ~SmartFactorBase() {
115  }
116 
122  void add(const Z& measured, const Key& key) {
123  if(std::find(keys_.begin(), keys_.end(), key) != keys_.end()) {
124  throw std::invalid_argument(
125  "SmartFactorBase::add: adding duplicate measurement for key.");
126  }
127  this->measured_.push_back(measured);
128  this->keys_.push_back(key);
129  }
130 
134  void add(ZVector& measurements, KeyVector& cameraKeys) {
135  for (size_t i = 0; i < measurements.size(); i++) {
136  this->add(measurements.at(i), cameraKeys.at(i));
137  }
138  }
139 
144  template<class SFM_TRACK>
145  void add(const SFM_TRACK& trackToAdd) {
146  for (size_t k = 0; k < trackToAdd.number_measurements(); k++) {
147  this->measured_.push_back(trackToAdd.measurements[k].second);
148  this->keys_.push_back(trackToAdd.measurements[k].first);
149  }
150  }
151 
153  size_t dim() const override {
154  return ZDim * this->measured_.size();
155  }
156 
158  const ZVector& measured() const {
159  return measured_;
160  }
161 
163  virtual Cameras cameras(const Values& values) const {
165  for(const Key& k: this->keys_)
166  cameras.push_back(values.at<CAMERA>(k));
167  return cameras;
168  }
169 
175  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
176  DefaultKeyFormatter) const override {
177  std::cout << s << "SmartFactorBase, z = \n";
178  for (size_t k = 0; k < measured_.size(); ++k) {
179  std::cout << "measurement, p = " << measured_[k] << "\t";
180  noiseModel_->print("noise model = ");
181  }
182  if(body_P_sensor_)
183  body_P_sensor_->print("body_P_sensor_:\n");
184  Base::print("", keyFormatter);
185  }
186 
188  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
189  const This *e = dynamic_cast<const This*>(&p);
190 
191  bool areMeasurementsEqual = true;
192  for (size_t i = 0; i < measured_.size(); i++) {
193  if (traits<Z>::Equals(this->measured_.at(i), e->measured_.at(i), tol) == false)
194  areMeasurementsEqual = false;
195  break;
196  }
197  return e && Base::equals(p, tol) && areMeasurementsEqual;
198  }
199 
202  template <class POINT>
204  const Cameras& cameras, const POINT& point,
205  boost::optional<typename Cameras::FBlocks&> Fs = boost::none, //
206  boost::optional<Matrix&> E = boost::none) const {
207  Vector ue = cameras.reprojectionError(point, measured_, Fs, E);
208  if (body_P_sensor_ && Fs) {
209  const Pose3 sensor_P_body = body_P_sensor_->inverse();
210  constexpr int camera_dim = traits<CAMERA>::dimension;
211  constexpr int pose_dim = traits<Pose3>::dimension;
212 
213  for (size_t i = 0; i < Fs->size(); i++) {
214  const Pose3 world_P_body = cameras[i].pose() * sensor_P_body;
215  Eigen::Matrix<double, camera_dim, camera_dim> J;
216  J.setZero();
217  Eigen::Matrix<double, pose_dim, pose_dim> H;
218  // Call compose to compute Jacobian for camera extrinsics
219  world_P_body.compose(*body_P_sensor_, H);
220  // Assign extrinsics part of the Jacobian
221  J.template block<pose_dim, pose_dim>(0, 0) = H;
222  Fs->at(i) = Fs->at(i) * J;
223  }
224  }
226  return ue;
227  }
228 
233  virtual void correctForMissingMeasurements(const Cameras& cameras, Vector& ue, boost::optional<typename Cameras::FBlocks&> Fs = boost::none,
234  boost::optional<Matrix&> E = boost::none) const {}
235 
240  template<class POINT>
241  Vector whitenedError(const Cameras& cameras, const POINT& point) const {
242  Vector e = cameras.reprojectionError(point, measured_);
243  if (noiseModel_)
244  noiseModel_->whitenInPlace(e);
245  return e;
246  }
247 
254  template<class POINT>
256  const POINT& point) const {
257  Vector e = whitenedError(cameras, point);
258  return 0.5 * e.dot(e);
259  }
260 
262  static Matrix PointCov(Matrix& E) {
263  return (E.transpose() * E).inverse();
264  }
265 
272  template<class POINT>
273  void computeJacobians(FBlocks& Fs, Matrix& E, Vector& b,
274  const Cameras& cameras, const POINT& point) const {
275  // Project into Camera set and calculate derivatives
276  // As in expressionFactor, RHS vector b = - (h(x_bar) - z) = z-h(x_bar)
277  // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z|
278  // = |A*dx - (z-h(x_bar))|
279  b = -unwhitenedError(cameras, point, Fs, E);
280  }
281 
283  template<class POINT>
284  void computeJacobiansSVD(FBlocks& Fs, Matrix& Enull,
285  Vector& b, const Cameras& cameras, const POINT& point) const {
286 
287  Matrix E;
288  computeJacobians(Fs, E, b, cameras, point);
289 
290  static const int N = FixedDimension<POINT>::value; // 2 (Unit3) or 3 (Point3)
291 
292  // Do SVD on A
293  Eigen::JacobiSVD<Matrix> svd(E, Eigen::ComputeFullU);
294  Vector s = svd.singularValues();
295  size_t m = this->keys_.size();
296  Enull = svd.matrixU().block(0, N, ZDim * m, ZDim * m - N); // last ZDim*m-N columns
297  }
298 
300  boost::shared_ptr<RegularHessianFactor<Dim> > createHessianFactor(
301  const Cameras& cameras, const Point3& point, const double lambda = 0.0,
302  bool diagonalDamping = false) const {
303 
304  Matrix E;
305  Vector b;
306  computeJacobians(Fs, E, b, cameras, point);
307 
308  // build augmented hessian
309  SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fs, E, b);
310 
311  return boost::make_shared<RegularHessianFactor<Dim> >(keys_,
312  augmentedHessian);
313  }
314 
320  void updateAugmentedHessian(const Cameras& cameras, const Point3& point,
321  const double lambda, bool diagonalDamping,
322  SymmetricBlockMatrix& augmentedHessian,
323  const KeyVector allKeys) const {
324  Matrix E;
325  Vector b;
326  computeJacobians(Fs, E, b, cameras, point);
327  Cameras::UpdateSchurComplement(Fs, E, b, allKeys, keys_, augmentedHessian);
328  }
329 
331  void whitenJacobians(FBlocks& F, Matrix& E, Vector& b) const {
332  noiseModel_->WhitenSystem(E, b);
333  // TODO make WhitenInPlace work with any dense matrix type
334  for (size_t i = 0; i < F.size(); i++)
335  F[i] = noiseModel_->Whiten(F[i]);
336  }
337 
339  boost::shared_ptr<RegularImplicitSchurFactor<CAMERA> > //
341  double lambda = 0.0, bool diagonalDamping = false) const {
342  Matrix E;
343  Vector b;
344  FBlocks F;
345  computeJacobians(F, E, b, cameras, point);
346  whitenJacobians(F, E, b);
347  Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
348  return boost::make_shared<RegularImplicitSchurFactor<CAMERA> >(keys_, F, E,
349  P, b);
350  }
351 
355  boost::shared_ptr<JacobianFactorQ<Dim, ZDim> > createJacobianQFactor(
356  const Cameras& cameras, const Point3& point, double lambda = 0.0,
357  bool diagonalDamping = false) const {
358  Matrix E;
359  Vector b;
360  FBlocks F;
361  computeJacobians(F, E, b, cameras, point);
362  const size_t M = b.size();
363  Matrix P = Cameras::PointCov(E, lambda, diagonalDamping);
364  SharedIsotropic n = noiseModel::Isotropic::Sigma(M, noiseModel_->sigma());
365  return boost::make_shared<JacobianFactorQ<Dim, ZDim> >(keys_, F, E, P, b, n);
366  }
367 
372  boost::shared_ptr<JacobianFactor> createJacobianSVDFactor(
373  const Cameras& cameras, const Point3& point, double lambda = 0.0) const {
374  size_t m = this->keys_.size();
375  FBlocks F;
376  Vector b;
377  const size_t M = ZDim * m;
378  Matrix E0(M, M - 3);
379  computeJacobiansSVD(F, E0, b, cameras, point);
380  SharedIsotropic n = noiseModel::Isotropic::Sigma(M - 3,
381  noiseModel_->sigma());
382  return boost::make_shared<JacobianFactorSVD<Dim, ZDim> >(keys_, F, E0, b, n);
383  }
384 
386  static void FillDiagonalF(const FBlocks& Fs, Matrix& F) {
387  size_t m = Fs.size();
388  F.resize(ZDim * m, Dim * m);
389  F.setZero();
390  for (size_t i = 0; i < m; ++i)
391  F.block<ZDim, Dim>(ZDim * i, Dim * i) = Fs.at(i);
392  }
393 
394 
395  Pose3 body_P_sensor() const{
396  if(body_P_sensor_)
397  return *body_P_sensor_;
398  else
399  return Pose3(); // if unspecified, the transformation is the identity
400  }
401 
402 private:
403 
405  friend class boost::serialization::access;
406  template<class ARCHIVE>
407  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
408  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
409  ar & BOOST_SERIALIZATION_NVP(noiseModel_);
410  ar & BOOST_SERIALIZATION_NVP(measured_);
411  ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
412  }
413 };
414 // end class SmartFactorBase
415 
416 // Definitions need to avoid link errors (above are only declarations)
417 template<class CAMERA> const int SmartFactorBase<CAMERA>::Dim;
418 template<class CAMERA> const int SmartFactorBase<CAMERA>::ZDim;
419 
420 } // \ namespace gtsam
gtsam::SmartFactorBase::ZDim
static const int ZDim
Measurement dimension.
Definition: SmartFactorBase.h:58
RegularHessianFactor.h
HessianFactor class with constant sized blocks.
gtsam::SmartFactorBase::createRegularImplicitSchurFactor
boost::shared_ptr< RegularImplicitSchurFactor< CAMERA > > createRegularImplicitSchurFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
Return Jacobians as RegularImplicitSchurFactor with raw access.
Definition: SmartFactorBase.h:340
gtsam::SmartFactorBase::totalReprojectionError
double totalReprojectionError(const Cameras &cameras, const POINT &point) const
Calculate the error of the factor.
Definition: SmartFactorBase.h:255
gtsam::SmartFactorBase::measured_
ZVector measured_
2D measurement and noise model for each of the m views We keep a copy of measurements for I/O and com...
Definition: SmartFactorBase.h:76
gtsam::NonlinearFactor::print
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print
Definition: NonlinearFactor.cpp:26
gtsam::SmartFactorBase::add
void add(const Z &measured, const Key &key)
Add a new measurement and pose/camera key.
Definition: SmartFactorBase.h:122
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:734
gtsam::traits
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
gtsam::SmartFactorBase::SmartFactorBase
SmartFactorBase(const SharedNoiseModel &sharedNoiseModel, boost::optional< Pose3 > body_P_sensor=boost::none, size_t expectedNumberCameras=10)
Constructor.
Definition: SmartFactorBase.h:96
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
gtsam::SmartFactorBase::createJacobianQFactor
boost::shared_ptr< JacobianFactorQ< Dim, ZDim > > createJacobianQFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0, bool diagonalDamping=false) const
Return Jacobians as JacobianFactorQ.
Definition: SmartFactorBase.h:355
gtsam::noiseModel::Isotropic
An isotropic noise model corresponds to a scaled diagonal covariance To construct,...
Definition: NoiseModel.h:526
gtsam::CameraSet::PointCov
static Matrix PointCov(const Matrix &E, const double lambda=0.0, bool diagonalDamping=false)
Computes Point Covariance P, with lambda parameter, dynamic version.
Definition: CameraSet.h:210
gtsam::Factor::keys_
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
gtsam::CameraSet
A set of cameras, all with their own calibration.
Definition: CameraSet.h:35
gtsam::FixedDimension
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
gtsam::SmartFactorBase::measured
const ZVector & measured() const
return the measurements
Definition: SmartFactorBase.h:158
gtsam::SmartFactorBase::shared_ptr
GTSAM_MAKE_ALIGNED_OPERATOR_NEW typedef boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartFactorBase.h:87
gtsam
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
CameraSet.h
Base class to create smart factors on poses or cameras.
gtsam::SmartFactorBase::cameras
virtual Cameras cameras(const Values &values) const
Collect all cameras: important that in key order.
Definition: SmartFactorBase.h:163
gtsam::SmartFactorBase::updateAugmentedHessian
void updateAugmentedHessian(const Cameras &cameras, const Point3 &point, const double lambda, bool diagonalDamping, SymmetricBlockMatrix &augmentedHessian, const KeyVector allKeys) const
Add the contribution of the smart factor to a pre-allocated Hessian, using sparse linear algebra.
Definition: SmartFactorBase.h:320
gtsam::CameraSet::reprojectionError
Vector reprojectionError(const POINT &point, const ZVector &measured, boost::optional< FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Calculate vector [project2(point)-z] of re-projection errors.
Definition: CameraSet.h:136
gtsam::NonlinearFactor
Nonlinear factor base class.
Definition: NonlinearFactor.h:43
gtsam::svd
void svd(const Matrix &A, Matrix &U, Vector &S, Matrix &V)
SVD computes economy SVD A=U*S*V'.
Definition: Matrix.cpp:559
NonlinearFactor.h
Non-linear factor base classes.
gtsam::SmartFactorBase::whitenJacobians
void whitenJacobians(FBlocks &F, Matrix &E, Vector &b) const
Whiten the Jacobians computed by computeJacobians using noiseModel_.
Definition: SmartFactorBase.h:331
gtsam::SmartFactorBase::add
void add(ZVector &measurements, KeyVector &cameraKeys)
Add a bunch of measurements, together with the camera keys.
Definition: SmartFactorBase.h:134
gtsam::SmartFactorBase::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: SmartFactorBase.h:175
gtsam::SmartFactorBase::createHessianFactor
boost::shared_ptr< RegularHessianFactor< Dim > > createHessianFactor(const Cameras &cameras, const Point3 &point, const double lambda=0.0, bool diagonalDamping=false) const
Linearize to a Hessianfactor.
Definition: SmartFactorBase.h:300
gtsam::Values::at
ValueType at(Key j) const
Retrieve a variable by key j.
Definition: Values-inl.h:342
gtsam::SmartFactorBase::PointCov
static Matrix PointCov(Matrix &E)
Computes Point Covariance P from E.
Definition: SmartFactorBase.h:262
gtsam::SmartFactorBase::FillDiagonalF
static void FillDiagonalF(const FBlocks &Fs, Matrix &F)
Create BIG block-diagonal matrix F from Fblocks.
Definition: SmartFactorBase.h:386
gtsam::SmartFactorBase::correctForMissingMeasurements
virtual void correctForMissingMeasurements(const Cameras &cameras, Vector &ue, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
This corrects the Jacobians for the case in which some pixel measurement is missing (nan) In practice...
Definition: SmartFactorBase.h:233
gtsam::SmartFactorBase::computeJacobiansSVD
void computeJacobiansSVD(FBlocks &Fs, Matrix &Enull, Vector &b, const Cameras &cameras, const POINT &point) const
SVD version.
Definition: SmartFactorBase.h:284
gtsam::SmartFactorBase::SmartFactorBase
SmartFactorBase()
Default Constructor, for serialization.
Definition: SmartFactorBase.h:93
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
This marks a GTSAM object to require alignment.
Definition: types.h:269
gtsam::SmartFactorBase::noiseModel_
SharedIsotropic noiseModel_
As of Feb 22, 2015, the noise model is the same for all measurements and is isotropic.
Definition: SmartFactorBase.h:69
gtsam::SmartFactorBase::~SmartFactorBase
virtual ~SmartFactorBase()
Virtual destructor, subclasses from NonlinearFactor.
Definition: SmartFactorBase.h:114
gtsam::Pose3
Definition: Pose3.h:37
gtsam::KeyFormatter
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::CameraSet::UpdateSchurComplement
static void UpdateSchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b, const KeyVector &allKeys, const KeyVector &keys, SymmetricBlockMatrix &augmentedHessian)
Applies Schur complement (exploiting block structure) to get a smart factor on cameras,...
Definition: CameraSet.h:246
gtsam::Factor
This is the base class for all factor types.
Definition: Factor.h:55
gtsam::SmartFactorBase
Base class for smart factors This base class has no internal point, but it has a measurement,...
Definition: SmartFactorBase.h:47
gtsam::SmartFactorBase::equals
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: SmartFactorBase.h:188
gtsam::SmartFactorBase::unwhitenedError
Vector unwhitenedError(const Cameras &cameras, const POINT &point, boost::optional< typename Cameras::FBlocks & > Fs=boost::none, boost::optional< Matrix & > E=boost::none) const
Compute reprojection errors [h(x)-z] = [cameras.project(p)-z] and derivatives.
Definition: SmartFactorBase.h:203
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
gtsam::Point3
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
gtsam::SmartFactorBase::createJacobianSVDFactor
boost::shared_ptr< JacobianFactor > createJacobianSVDFactor(const Cameras &cameras, const Point3 &point, double lambda=0.0) const
Return Jacobians as JacobianFactorSVD TODO lambda is currently ignored.
Definition: SmartFactorBase.h:372
gtsam::SymmetricBlockMatrix
Definition: SymmetricBlockMatrix.h:52
gtsam::SmartFactorBase::Dim
static const int Dim
Camera dimension.
Definition: SmartFactorBase.h:57
gtsam::SmartFactorBase::Cameras
CameraSet< CAMERA > Cameras
We use the new CameraSte data structure to refer to a set of cameras.
Definition: SmartFactorBase.h:90
gtsam::Values
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:71
gtsam::SmartFactorBase::whitenedError
Vector whitenedError(const Cameras &cameras, const POINT &point) const
Calculate vector of re-projection errors [h(x)-z] = [cameras.project(p) - z] Noise model applied.
Definition: SmartFactorBase.h:241
gtsam::CameraSet::SchurComplement
static SymmetricBlockMatrix SchurComplement(const FBlocks &Fs, const Matrix &E, const Eigen::Matrix< double, N, N > &P, const Vector &b)
Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix G = F' * F - F' * E * P * ...
Definition: CameraSet.h:149
gtsam::SmartFactorBase::add
void add(const SFM_TRACK &trackToAdd)
Adds an entire SfM_track (collection of cameras observing a single point).
Definition: SmartFactorBase.h:145
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition: NoiseModel.cpp:567
RegularImplicitSchurFactor.h
A new type of linear factor (GaussianFactor), which is subclass of GaussianFactor.
gtsam::NonlinearFactor::equals
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Check if two factors are equal.
Definition: NonlinearFactor.cpp:36
gtsam::SmartFactorBase::dim
size_t dim() const override
get the dimension (number of rows!) of the factor
Definition: SmartFactorBase.h:153
gtsam::SmartFactorBase::computeJacobians
void computeJacobians(FBlocks &Fs, Matrix &E, Vector &b, const Cameras &cameras, const POINT &point) const
Compute F, E, and b (called below in both vanilla and SVD versions), where F is a vector of derivativ...
Definition: SmartFactorBase.h:273
gtsam::SmartFactorBase::body_P_sensor_
boost::optional< Pose3 > body_P_sensor_
Pose of the camera in the body frame.
Definition: SmartFactorBase.h:78