Order matters with inheritance
							parent
							
								
									5ce728ab46
								
							
						
					
					
						commit
						3cc6ebedd2
					
				| 
						 | 
				
			
			@ -68,7 +68,7 @@ class Values {
 | 
			
		|||
  // gtsam::Value at(size_t j) const;
 | 
			
		||||
 | 
			
		||||
  // The order is important: gtsam::Vector has to precede Point2/Point3 so `atVector`
 | 
			
		||||
  // can work for those fixed-size vectors.
 | 
			
		||||
  // can work for those fixed-size vectors. Same apparently for Cal3Bundler and Cal3f.
 | 
			
		||||
  void insert(size_t j, gtsam::Vector vector);
 | 
			
		||||
  void insert(size_t j, gtsam::Matrix matrix);
 | 
			
		||||
  void insert(size_t j, const gtsam::Point2& point2);
 | 
			
		||||
| 
						 | 
				
			
			@ -81,25 +81,25 @@ class Values {
 | 
			
		|||
  void insert(size_t j, const gtsam::Rot3& rot3);
 | 
			
		||||
  void insert(size_t j, const gtsam::Pose3& pose3);
 | 
			
		||||
  void insert(size_t j, const gtsam::Unit3& unit3);
 | 
			
		||||
  void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler);
 | 
			
		||||
  void insert(size_t j, const gtsam::Cal3f& cal3f);
 | 
			
		||||
  void insert(size_t j, const gtsam::Cal3_S2& cal3_s2);
 | 
			
		||||
  void insert(size_t j, const gtsam::Cal3DS2& cal3ds2);
 | 
			
		||||
  void insert(size_t j, const gtsam::Cal3Bundler& cal3bundler);
 | 
			
		||||
  void insert(size_t j, const gtsam::Cal3Fisheye& cal3fisheye);
 | 
			
		||||
  void insert(size_t j, const gtsam::Cal3Unified& cal3unified);
 | 
			
		||||
  void insert(size_t j, const gtsam::EssentialMatrix& E);
 | 
			
		||||
  void insert(size_t j, const gtsam::FundamentalMatrix& F);
 | 
			
		||||
  void insert(size_t j, const gtsam::SimpleFundamentalMatrix& F);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3f>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3_S2>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3DS2>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3f>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3_S2>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3DS2>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3Fisheye>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
 | 
			
		||||
  void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
 | 
			
		||||
| 
						 | 
				
			
			@ -123,25 +123,25 @@ class Values {
 | 
			
		|||
  void update(size_t j, const gtsam::Rot3& rot3);
 | 
			
		||||
  void update(size_t j, const gtsam::Pose3& pose3);
 | 
			
		||||
  void update(size_t j, const gtsam::Unit3& unit3);
 | 
			
		||||
  void update(size_t j, const gtsam::Cal3Bundler& cal3bundler);
 | 
			
		||||
  void update(size_t j, const gtsam::Cal3f& cal3f);
 | 
			
		||||
  void update(size_t j, const gtsam::Cal3_S2& cal3_s2);
 | 
			
		||||
  void update(size_t j, const gtsam::Cal3DS2& cal3ds2);
 | 
			
		||||
  void update(size_t j, const gtsam::Cal3Bundler& cal3bundler);
 | 
			
		||||
  void update(size_t j, const gtsam::Cal3Fisheye& cal3fisheye);
 | 
			
		||||
  void update(size_t j, const gtsam::Cal3Unified& cal3unified);
 | 
			
		||||
  void update(size_t j, const gtsam::EssentialMatrix& E);
 | 
			
		||||
  void update(size_t j, const gtsam::FundamentalMatrix& F);
 | 
			
		||||
  void update(size_t j, const gtsam::SimpleFundamentalMatrix& F);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3f>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3_S2>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3DS2>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholePose<gtsam::Cal3f>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholePose<gtsam::Cal3_S2>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholePose<gtsam::Cal3DS2>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Fisheye>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
 | 
			
		||||
  void update(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
 | 
			
		||||
| 
						 | 
				
			
			@ -162,41 +162,28 @@ class Values {
 | 
			
		|||
  void insert_or_assign(size_t j, const gtsam::Rot3& rot3);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Pose3& pose3);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Unit3& unit3);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Cal3Bundler& cal3bundler);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Cal3f& cal3f);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Cal3_S2& cal3_s2);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Cal3DS2& cal3ds2);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Cal3Bundler& cal3bundler);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Cal3Fisheye& cal3fisheye);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::Cal3Unified& cal3unified);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::EssentialMatrix& E);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::FundamentalMatrix& F);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::SimpleFundamentalMatrix& F);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholeCamera<gtsam::Cal3f>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholeCamera<gtsam::Cal3_S2>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholeCamera<gtsam::Cal3DS2>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholePose<gtsam::Cal3f>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholePose<gtsam::Cal3_S2>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholePose<gtsam::Cal3DS2>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholePose<gtsam::Cal3Fisheye>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j,
 | 
			
		||||
                        const gtsam::imuBias::ConstantBias& constant_bias);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3f>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3_S2>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3DS2>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Fisheye>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholeCamera<gtsam::Cal3Unified>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3Bundler>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3f>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3_S2>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3DS2>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3Fisheye>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::PinholePose<gtsam::Cal3Unified>& camera);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::imuBias::ConstantBias& constant_bias);
 | 
			
		||||
  void insert_or_assign(size_t j, const gtsam::NavState& nav_state);
 | 
			
		||||
  void insert_or_assign(size_t j, double c);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -210,25 +197,25 @@ class Values {
 | 
			
		|||
                 gtsam::Rot3,
 | 
			
		||||
                 gtsam::Pose3,
 | 
			
		||||
                 gtsam::Unit3,
 | 
			
		||||
                 gtsam::Cal3Bundler,
 | 
			
		||||
                 gtsam::Cal3f, 
 | 
			
		||||
                 gtsam::Cal3_S2,
 | 
			
		||||
                 gtsam::Cal3DS2,
 | 
			
		||||
                 gtsam::Cal3Bundler,
 | 
			
		||||
                 gtsam::Cal3Fisheye,
 | 
			
		||||
                 gtsam::Cal3Unified,
 | 
			
		||||
                 gtsam::EssentialMatrix, 
 | 
			
		||||
                 gtsam::FundamentalMatrix, 
 | 
			
		||||
                 gtsam::SimpleFundamentalMatrix,
 | 
			
		||||
                 gtsam::PinholeCamera<gtsam::Cal3Bundler>,
 | 
			
		||||
                 gtsam::PinholeCamera<gtsam::Cal3f>,
 | 
			
		||||
                 gtsam::PinholeCamera<gtsam::Cal3_S2>,
 | 
			
		||||
                 gtsam::PinholeCamera<gtsam::Cal3DS2>,
 | 
			
		||||
                 gtsam::PinholeCamera<gtsam::Cal3Bundler>,
 | 
			
		||||
                 gtsam::PinholeCamera<gtsam::Cal3Fisheye>,
 | 
			
		||||
                 gtsam::PinholeCamera<gtsam::Cal3Unified>,
 | 
			
		||||
                 gtsam::PinholePose<gtsam::Cal3Bundler>,
 | 
			
		||||
                 gtsam::PinholePose<gtsam::Cal3f>,
 | 
			
		||||
                 gtsam::PinholePose<gtsam::Cal3_S2>,
 | 
			
		||||
                 gtsam::PinholePose<gtsam::Cal3DS2>,
 | 
			
		||||
                 gtsam::PinholePose<gtsam::Cal3Bundler>,
 | 
			
		||||
                 gtsam::PinholePose<gtsam::Cal3Fisheye>,
 | 
			
		||||
                 gtsam::PinholePose<gtsam::Cal3Unified>,
 | 
			
		||||
                 gtsam::imuBias::ConstantBias,
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
		Reference in New Issue