diff --git a/demos/demo_2_lasers_offline.cpp b/demos/demo_2_lasers_offline.cpp index 40ebda489e205e21154a7501f3becacb6b8caced..16626151661e3af3700efedce76a9d5bf61657c7 100644 --- a/demos/demo_2_lasers_offline.cpp +++ b/demos/demo_2_lasers_offline.cpp @@ -115,7 +115,7 @@ int main(int argc, char** argv) Eigen::VectorXd laser_1_pose2D(3), laser_2_pose2D(3); //xy + theta // odometry intrinsics - IntrinsicsOdom2D odom_intrinsics; + ParamsSensorOdom2D odom_intrinsics; odom_intrinsics.k_disp_to_disp = odom_std_factor; odom_intrinsics.k_rot_to_rot = odom_std_factor; @@ -125,7 +125,7 @@ int main(int argc, char** argv) laser_1_pose2D.head<2>() = laser_1_pose.head<2>(); laser_1_pose2D(2) = laser_1_pose(3); std::vector<float> scan1(laser_1_params(8)); // number of ranges in a scan - IntrinsicsLaser2D laser_1_intrinsics; + ParamsSensorLaser2D laser_1_intrinsics; laser_1_intrinsics.scan_params = laserscanutils::LaserScanParams({laser_1_params(0), laser_1_params(1), laser_1_params(2), laser_1_params(3), laser_1_params(4), laser_1_params(5), laser_1_params(6), laser_1_params(7)}); ProcessorParamsLaser laser_1_processor_params; @@ -138,7 +138,7 @@ int main(int argc, char** argv) laser_2_pose2D.head<2>() = laser_2_pose.head<2>(); laser_2_pose2D(2) = laser_2_pose(3); std::vector<float> scan2(laser_2_params(8)); - IntrinsicsLaser2D laser_2_intrinsics; + ParamsSensorLaser2D laser_2_intrinsics; laser_2_intrinsics.scan_params = laserscanutils::LaserScanParams({laser_2_params(0), laser_2_params(1), laser_2_params(2), laser_2_params(3), laser_2_params(4), laser_2_params(5), laser_2_params(6), laser_2_params(7)}); ProcessorParamsLaser laser_2_processor_params; diff --git a/demos/demo_diff_drive.cpp b/demos/demo_diff_drive.cpp index 65a9dcf35ff17db6faa1195fddeca09373ea3350..4b8b77b4edd289233a8522d0b6cc742072bb487a 100644 --- a/demos/demo_diff_drive.cpp +++ b/demos/demo_diff_drive.cpp @@ -169,10 +169,10 @@ int main(int argc, char** argv) Eigen::VectorXd extrinsics(3); extrinsics << 0, 0, 0; - IntrinsicsBasePtr intrinsics = std::make_shared<IntrinsicsDiffDrive>(); + ParamsSensorBasePtr intrinsics = std::make_shared<ParamsSensorDiffDrive>(); - IntrinsicsDiffDrivePtr intrinsics_diff_drive = - std::static_pointer_cast<IntrinsicsDiffDrive>(intrinsics); + ParamsSensorDiffDrivePtr intrinsics_diff_drive = + std::static_pointer_cast<ParamsSensorDiffDrive>(intrinsics); intrinsics_diff_drive->left_radius_ = 0.1; intrinsics_diff_drive->right_radius_ = 0.1; diff --git a/demos/demo_factor_imu.cpp b/demos/demo_factor_imu.cpp index f99b44448fb07d337a0319b3bb451560daf19c76..d8ab22bd322f6dd262f66a639647fb41159d27b1 100644 --- a/demos/demo_factor_imu.cpp +++ b/demos/demo_factor_imu.cpp @@ -26,7 +26,7 @@ int main(int argc, char** argv) ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D"); Eigen::VectorXd IMU_extrinsics(7); IMU_extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot - SensorBasePtr sensor_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", IMU_extrinsics, shared_ptr<IntrinsicsBase>()); + SensorBasePtr sensor_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", IMU_extrinsics, shared_ptr<ParamsSensorBase>()); wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", ""); // Ceres wrappers diff --git a/demos/demo_mpu.cpp b/demos/demo_mpu.cpp index dbbeb886e8b1d505206053a84fa53e7f67102742..16b74b5cb2866e5b36f25d931cfd0eaedd40abf5 100644 --- a/demos/demo_mpu.cpp +++ b/demos/demo_mpu.cpp @@ -105,7 +105,7 @@ int main(int argc, char** argv) ProblemPtr wolf_problem_ptr_ = Problem::create("PQVBB 3D"); Eigen::VectorXd IMU_extrinsics(7); IMU_extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot - SensorBasePtr sensor_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", IMU_extrinsics, IntrinsicsBase()); + SensorBasePtr sensor_ptr = wolf_problem_ptr_->installSensor("IMU", "Main IMU", IMU_extrinsics, ParamsSensorBase()); wolf_problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", ""); // Time and data variables diff --git a/demos/demo_processor_bundle_adjustment.cpp b/demos/demo_processor_bundle_adjustment.cpp index 1fd45f06a8550bf6670078050f06a71e48e19854..8d38f99baabdfa8767e201a912aade54a86966df 100644 --- a/demos/demo_processor_bundle_adjustment.cpp +++ b/demos/demo_processor_bundle_adjustment.cpp @@ -107,7 +107,7 @@ int main(int argc, char** argv) // Install camera -// IntrinsicsCameraPtr intr = std::make_shared<IntrinsicsCamera>(); // TODO init params or read from YAML +// ParamsSensorCameraPtr intr = std::make_shared<ParamsSensorCamera>(); // TODO init params or read from YAML // intr->pinhole_model_raw = Eigen::Vector4d(320,240,320,320); // intr->width = img_width; // intr->height = img_height; diff --git a/demos/demo_processor_imu.cpp b/demos/demo_processor_imu.cpp index e6062abbc6310e580e1623b9c01d851e4184a988..b6d13a30b8a0b06a8bbe54cf66166b1c3eef3782 100644 --- a/demos/demo_processor_imu.cpp +++ b/demos/demo_processor_imu.cpp @@ -73,7 +73,7 @@ int main(int argc, char** argv) ProblemPtr problem_ptr_ = Problem::create("PQVBB 3D"); Eigen::VectorXd extrinsics(7); extrinsics << 0,0,0, 0,0,0,1; // IMU pose in the robot - SensorBasePtr sensor_ptr = problem_ptr_->installSensor("IMU", "Main IMU", extrinsics, IntrinsicsBasePtr()); + SensorBasePtr sensor_ptr = problem_ptr_->installSensor("IMU", "Main IMU", extrinsics, ParamsSensorBasePtr()); problem_ptr_->installProcessor("IMU", "IMU pre-integrator", "Main IMU", ""); // Time and data variables diff --git a/demos/demo_sparsification.cpp b/demos/demo_sparsification.cpp index 5038ac3cf5fb95e8e96ab65f2732f2f83a47f389..eaa840df5cecaf334ca4982907013cfd5122b638 100644 --- a/demos/demo_sparsification.cpp +++ b/demos/demo_sparsification.cpp @@ -187,7 +187,7 @@ int main(int argc, char** argv) // Wolf problem FrameBasePtr last_frame_ptr, frame_from_ptr, frame_to_ptr; ProblemPtr bl_problem_ptr = Problem::create("PO_2D"); - SensorBasePtr sensor_ptr = bl_problem_ptr->installSensor("ODOM 2D", "Odometry", Eigen::VectorXd::Zero(3), IntrinsicsBasePtr()); + SensorBasePtr sensor_ptr = bl_problem_ptr->installSensor("ODOM 2D", "Odometry", Eigen::VectorXd::Zero(3), ParamsSensorBasePtr()); // Ceres wrapper std::string bl_summary, sp_summary; diff --git a/demos/demo_wolf_factories.cpp b/demos/demo_wolf_factories.cpp index a573759d216ca30beb25473deecd4ad916a2f02b..ddd2d26a78f4edb8ed4ce66d99fdf245f9ae4381 100644 --- a/demos/demo_wolf_factories.cpp +++ b/demos/demo_wolf_factories.cpp @@ -54,15 +54,15 @@ int main(void) // define some useful parameters Eigen::VectorXd pq_3d(7), po_2d(3), p_3d(3); - shared_ptr<IntrinsicsOdom2D> intr_odom2d_ptr = nullptr; + shared_ptr<ParamsSensorOdom2D> intr_odom2d_ptr = nullptr; - cout << "\n================== Intrinsics Factory ===================" << endl; + cout << "\n================== ParamsSensor Factory ===================" << endl; // Use params factory for camera intrinsics - IntrinsicsBasePtr intr_cam_ptr = IntrinsicsFactory::get().create("CAMERA", wolf_config + "/camera_params_ueye_sim.yaml"); + ParamsSensorBasePtr intr_cam_ptr = ParamsSensorFactory::get().create("CAMERA", wolf_config + "/camera_params_ueye_sim.yaml"); ProcessorParamsBasePtr params_ptr = ProcessorParamsFactory::get().create("IMAGE FEATURE", wolf_config + "/processor_image_feature.yaml"); - cout << "CAMERA with intrinsics : " << (static_pointer_cast<IntrinsicsCamera>(intr_cam_ptr))->pinhole_model_raw.transpose() << endl; + cout << "CAMERA with intrinsics : " << (static_pointer_cast<ParamsSensorCamera>(intr_cam_ptr))->pinhole_model_raw.transpose() << endl; // cout << "Processor IMAGE image width : " << (static_pointer_cast<ProcessorParamsImage>(params_ptr))->image.width << endl; cout << "\n==================== Install Sensors ====================" << endl; diff --git a/include/vision/sensor/sensor_camera.h b/include/vision/sensor/sensor_camera.h index f0ff33b48a3eff87343e5057a2710c70393eb9ba..f0319260d2f3c7663a5190d0883ced96141e71d7 100644 --- a/include/vision/sensor/sensor_camera.h +++ b/include/vision/sensor/sensor_camera.h @@ -8,22 +8,22 @@ namespace wolf { -WOLF_STRUCT_PTR_TYPEDEFS(IntrinsicsCamera); +WOLF_STRUCT_PTR_TYPEDEFS(ParamsSensorCamera); /** Struct of intrinsic camera parameters */ -struct IntrinsicsCamera : public IntrinsicsBase +struct ParamsSensorCamera : public ParamsSensorBase { unsigned int width; ///< Image width in pixels unsigned int height; ///< Image height in pixels Eigen::Vector4d pinhole_model_raw; ///< k = [u_0, v_0, alpha_u, alpha_v] vector of pinhole intrinsic parameters Eigen::Vector4d pinhole_model_rectified;///< k = [u_0, v_0, alpha_u, alpha_v] vector of pinhole intrinsic parameters Eigen::VectorXd distortion; ///< d = [d_1, d_2, d_3, ...] radial distortion coefficients - IntrinsicsCamera() + ParamsSensorCamera() { //DEFINED FOR COMPATIBILITY PURPOSES. TO BE REMOVED IN THE FUTURE. } - IntrinsicsCamera(std::string _unique_name, const ParamsServer& _server): - IntrinsicsBase(_unique_name, _server) + ParamsSensorCamera(std::string _unique_name, const ParamsServer& _server): + ParamsSensorBase(_unique_name, _server) { width = _server.getParam<unsigned int>(_unique_name + "/width"); height = _server.getParam<unsigned int>(_unique_name + "/height"); @@ -33,14 +33,14 @@ struct IntrinsicsCamera : public IntrinsicsBase } std::string print() const { - return "\n" + IntrinsicsBase::print() + "\n" + return "\n" + ParamsSensorBase::print() + "\n" + "width: " + std::to_string(width) + "\n" + "height: " + std::to_string(height) + "\n" + "pinhole: " + converter<std::string>::convert(pinhole_model_raw) + "\n" + "pinhole: " + converter<std::string>::convert(pinhole_model_rectified) + "\n" + "distortion: " + converter<std::string>::convert(distortion) + "\n"; } - virtual ~IntrinsicsCamera() = default; + virtual ~ParamsSensorCamera() = default; }; WOLF_PTR_TYPEDEFS(SensorCamera); @@ -50,8 +50,8 @@ class SensorCamera : public SensorBase { public: - SensorCamera(const Eigen::VectorXd & _extrinsics, const IntrinsicsCamera& _intrinsics); - SensorCamera(const Eigen::VectorXd & _extrinsics, IntrinsicsCameraPtr _intrinsics_ptr); + SensorCamera(const Eigen::VectorXd & _extrinsics, const ParamsSensorCamera& _intrinsics); + SensorCamera(const Eigen::VectorXd & _extrinsics, ParamsSensorCameraPtr _intrinsics_ptr); virtual ~SensorCamera(); @@ -85,7 +85,7 @@ class SensorCamera : public SensorBase static SensorBasePtr create(const std::string & _unique_name, // const Eigen::VectorXd& _extrinsics, // - const IntrinsicsBasePtr _intrinsics); + const ParamsSensorBasePtr _intrinsics); }; diff --git a/src/sensor/sensor_camera.cpp b/src/sensor/sensor_camera.cpp index 2715173b5317dc8c1a687cf03413190e4cd7bb81..317159e9640a86c5030de3faebdcb5884c136cc4 100644 --- a/src/sensor/sensor_camera.cpp +++ b/src/sensor/sensor_camera.cpp @@ -8,7 +8,7 @@ namespace wolf { -SensorCamera::SensorCamera(const Eigen::VectorXd& _extrinsics, const IntrinsicsCamera& _intrinsics) : +SensorCamera::SensorCamera(const Eigen::VectorXd& _extrinsics, const ParamsSensorCamera& _intrinsics) : SensorBase("CAMERA", std::make_shared<StateBlock>(_extrinsics.head(3), true), std::make_shared<StateQuaternion>(_extrinsics.tail(4), true), std::make_shared<StateBlock>(_intrinsics.pinhole_model_raw, true), 1), img_width_(_intrinsics.width), // img_height_(_intrinsics.height), // @@ -23,7 +23,7 @@ SensorCamera::SensorCamera(const Eigen::VectorXd& _extrinsics, const IntrinsicsC pinhole::computeCorrectionModel(getIntrinsic()->getState(), distortion_, correction_); } -SensorCamera::SensorCamera(const Eigen::VectorXd& _extrinsics, IntrinsicsCameraPtr _intrinsics_ptr) : +SensorCamera::SensorCamera(const Eigen::VectorXd& _extrinsics, ParamsSensorCameraPtr _intrinsics_ptr) : SensorCamera(_extrinsics, *_intrinsics_ptr) { // @@ -50,11 +50,11 @@ Eigen::Matrix3d SensorCamera::setIntrinsicMatrix(Eigen::Vector4d _pinhole_model) // Define the factory method SensorBasePtr SensorCamera::create(const std::string& _unique_name, // const Eigen::VectorXd& _extrinsics_pq, // - const IntrinsicsBasePtr _intrinsics) + const ParamsSensorBasePtr _intrinsics) { assert(_extrinsics_pq.size() == 7 && "Bad extrinsics vector length. Should be 7 for 3D."); - std::shared_ptr<IntrinsicsCamera> intrinsics_ptr = std::static_pointer_cast<IntrinsicsCamera>(_intrinsics); + std::shared_ptr<ParamsSensorCamera> intrinsics_ptr = std::static_pointer_cast<ParamsSensorCamera>(_intrinsics); SensorCameraPtr sen_ptr = std::make_shared<SensorCamera>(_extrinsics_pq, intrinsics_ptr); sen_ptr->setName(_unique_name); diff --git a/src/yaml/sensor_camera_yaml.cpp b/src/yaml/sensor_camera_yaml.cpp index e9e951dff8ce49548ef6de2d82591a894b28b14b..68797cfbb80144ca2473e54af91bab41ea0219cd 100644 --- a/src/yaml/sensor_camera_yaml.cpp +++ b/src/yaml/sensor_camera_yaml.cpp @@ -20,7 +20,7 @@ namespace wolf namespace { -static IntrinsicsBasePtr createIntrinsicsCamera(const std::string & _filename_dot_yaml) +static ParamsSensorBasePtr createParamsSensorCamera(const std::string & _filename_dot_yaml) { YAML::Node camera_config = YAML::LoadFile(_filename_dot_yaml); @@ -37,7 +37,7 @@ static IntrinsicsBasePtr createIntrinsicsCamera(const std::string & _filename_do VectorXd projection = camera_config["projection_matrix"]["data"] .as<VectorXd>(); // Eigen:: to wolf:: - std::shared_ptr<IntrinsicsCamera> intrinsics_cam = std::make_shared<IntrinsicsCamera>(); + std::shared_ptr<ParamsSensorCamera> intrinsics_cam = std::make_shared<ParamsSensorCamera>(); intrinsics_cam->width = width; intrinsics_cam->height = height; @@ -106,7 +106,7 @@ static IntrinsicsBasePtr createIntrinsicsCamera(const std::string & _filename_do } // Register in the SensorFactory -const bool WOLF_UNUSED registered_camera_intr = IntrinsicsFactory::get().registerCreator("CAMERA", createIntrinsicsCamera); +const bool WOLF_UNUSED registered_camera_intr = ParamsSensorFactory::get().registerCreator("CAMERA", createParamsSensorCamera); } // namespace [unnamed] diff --git a/test/gtest_factor_epipolar.cpp b/test/gtest_factor_epipolar.cpp index 0c29c57f68848860c3bae38d88ed23de80cb8d58..a5e74cb9bc773d41f41bb4676a94c13d4ed91788 100644 --- a/test/gtest_factor_epipolar.cpp +++ b/test/gtest_factor_epipolar.cpp @@ -33,7 +33,7 @@ TEST(FactorEpipolar, exemple) auto P = Problem::create("PO", 3); // Install sensor and processor - IntrinsicsCameraPtr intr = std::make_shared<IntrinsicsCamera>(); + ParamsSensorCameraPtr intr = std::make_shared<ParamsSensorCamera>(); intr->pinhole_model_raw = Eigen::Vector4d(320,240,320,320); intr->pinhole_model_rectified = Eigen::Vector4d(320,240,320,320); intr->width = 640; diff --git a/test/gtest_factor_pixelHP.cpp b/test/gtest_factor_pixelHP.cpp index 63c589139ece552e2abb032af413293373423095..853cb9c9025458fa65fc6ee171a071d0f35b5783 100644 --- a/test/gtest_factor_pixelHP.cpp +++ b/test/gtest_factor_pixelHP.cpp @@ -154,7 +154,7 @@ class FactorPixelHPTest : public testing::Test{ // Install sensor and processor - IntrinsicsCameraPtr intr = std::make_shared<IntrinsicsCamera>(); + ParamsSensorCameraPtr intr = std::make_shared<ParamsSensorCamera>(); intr->pinhole_model_raw = Eigen::Vector4d(320,240,320,320); intr->pinhole_model_rectified = Eigen::Vector4d(320,240,320,320); intr->width = 640; @@ -201,7 +201,7 @@ TEST(ProcessorFactorPixelHP, testZeroResidual) CeresManagerPtr ceres_mgr = std::make_shared<CeresManager>(problem_ptr); // Install sensor - IntrinsicsCameraPtr intr = std::make_shared<IntrinsicsCamera>(); + ParamsSensorCameraPtr intr = std::make_shared<ParamsSensorCamera>(); intr->pinhole_model_raw = Eigen::Vector4d(0,0,1,1); intr->pinhole_model_rectified = Eigen::Vector4d(320,240,320,320); intr->width = 640; diff --git a/test/gtest_processor_bundle_adjustment.cpp b/test/gtest_processor_bundle_adjustment.cpp index 767b5b2bd1d001d67d962ea7904e0be445825f2f..09d1ab3435eee9d540ec00df91aa047cd7ad7d30 100644 --- a/test/gtest_processor_bundle_adjustment.cpp +++ b/test/gtest_processor_bundle_adjustment.cpp @@ -100,7 +100,7 @@ TEST(ProcessorBundleAdjustment, installProcessor) ProblemPtr problem = Problem::create("PO", 3); // Install camera - IntrinsicsCameraPtr intr = std::make_shared<IntrinsicsCamera>(); // TODO init params or read from YAML + ParamsSensorCameraPtr intr = std::make_shared<ParamsSensorCamera>(); // TODO init params or read from YAML intr->width = 640; intr->height = 480; auto sens_cam = problem->installSensor("CAMERA", "camera", (Eigen::Vector7d() << 0,0,0, 0,0,0,1).finished(), intr); @@ -238,7 +238,7 @@ TEST(ProcessorBundleAdjustment, emplaceLandmark) ProblemPtr problem_ptr = Problem::create("PO", 3); // Install sensor - IntrinsicsCameraPtr intr = std::make_shared<IntrinsicsCamera>(); + ParamsSensorCameraPtr intr = std::make_shared<ParamsSensorCamera>(); intr->width = 640; intr->height = 480; auto sens_cam = problem_ptr->installSensor("CAMERA", "camera", (Eigen::Vector7d() << 0,0,0, 0,0,0,1).finished(), intr); @@ -282,7 +282,7 @@ TEST(ProcessorBundleAdjustment, process) ProblemPtr problem = Problem::create("PO", 3); // Install camera - IntrinsicsCameraPtr intr = std::make_shared<IntrinsicsCamera>(); // TODO init params or read from YAML + ParamsSensorCameraPtr intr = std::make_shared<ParamsSensorCamera>(); // TODO init params or read from YAML intr->pinhole_model_raw = Eigen::Vector4d(0,0,1,1); //TODO: initialize intr->width = 640; intr->height = 480; diff --git a/test/gtest_processor_tracker_feature_trifocal.cpp b/test/gtest_processor_tracker_feature_trifocal.cpp index c3286dcd94f8032cdc1fe2c6757b8cbe367c8cd8..314b315bf0138bfa2c2c3187737a412b3e0813e6 100644 --- a/test/gtest_processor_tracker_feature_trifocal.cpp +++ b/test/gtest_processor_tracker_feature_trifocal.cpp @@ -75,7 +75,7 @@ TEST(ProcessorTrackerFeatureTrifocal, KeyFrameCallback) ProblemPtr problem = Problem::create("PO", 3); // Install tracker (sensor and processor) - IntrinsicsCameraPtr intr = make_shared<IntrinsicsCamera>(); // TODO init params or read from YAML + ParamsSensorCameraPtr intr = make_shared<ParamsSensorCamera>(); // TODO init params or read from YAML intr->width = 640; intr->height = 480; // SensorCameraPtr sens_trk = make_shared<SensorCamera>((Eigen::Vector7d()<<0,0,0, 0,0,0,1).finished(), @@ -104,7 +104,7 @@ TEST(ProcessorTrackerFeatureTrifocal, KeyFrameCallback) // sens_trk->addProcessor(proc_trk); // Install odometer (sensor and processor) - IntrinsicsOdom3DPtr params = std::make_shared<IntrinsicsOdom3D>(); + ParamsSensorOdom3DPtr params = std::make_shared<ParamsSensorOdom3D>(); params->min_disp_var = 0.000001; params->min_rot_var = 0.000001; SensorBasePtr sens_odo = problem->installSensor("SensorOdom3D", "odometer", (Vector7d() << 0,0,0, 0,0,0,1).finished(), params); diff --git a/test/gtest_sensor_camera.cpp b/test/gtest_sensor_camera.cpp index fd068a9925a4bf1601656e5ecfd24b8b15a4f9ed..e3890984dd28cd6428cb73ca77f000323a1bb339 100644 --- a/test/gtest_sensor_camera.cpp +++ b/test/gtest_sensor_camera.cpp @@ -16,7 +16,7 @@ using namespace wolf; TEST(SensorCamera, Img_size) { Eigen::VectorXd extrinsics(7); extrinsics << 0,0,0, 0,0,0,1; - IntrinsicsCamera params; + ParamsSensorCamera params; params.width = 640; params.height = 480; SensorCameraPtr cam = std::make_shared<SensorCamera>(extrinsics, params); @@ -31,10 +31,10 @@ TEST(SensorCamera, Img_size) ASSERT_EQ(cam->getImgHeight(), 100); } -TEST(SensorCamera, Intrinsics_Raw_Rectified) +TEST(SensorCamera, ParamsSensor_Raw_Rectified) { Eigen::VectorXd extrinsics(7); extrinsics << 0,0,0, 0,0,0,1; - IntrinsicsCamera params; + ParamsSensorCamera params; params.pinhole_model_raw << 321, 241, 321, 321; params.pinhole_model_rectified << 320, 240, 320, 320; SensorCameraPtr cam = std::make_shared<SensorCamera>(extrinsics, params); @@ -64,7 +64,7 @@ TEST(SensorCamera, Intrinsics_Raw_Rectified) TEST(SensorCamera, Distortion) { Eigen::VectorXd extrinsics(7); extrinsics << 0,0,0, 0,0,0,1; - IntrinsicsCamera params; + ParamsSensorCamera params; params.width = 640; params.height = 480; params.pinhole_model_raw << 321, 241, 321, 321; @@ -80,7 +80,7 @@ TEST(SensorCamera, Distortion) TEST(SensorCamera, Correction_zero) { Eigen::VectorXd extrinsics(7); extrinsics << 0,0,0, 0,0,0,1; - IntrinsicsCamera params; + ParamsSensorCamera params; params.width = 640; params.height = 480; params.pinhole_model_raw << 321, 241, 321, 321; @@ -98,7 +98,7 @@ TEST(SensorCamera, Correction_zero) TEST(SensorCamera, create) { Eigen::VectorXd extrinsics(7); extrinsics << 0,0,0, 0,0,0,1; - IntrinsicsCameraPtr params = std::make_shared<IntrinsicsCamera>(); + ParamsSensorCameraPtr params = std::make_shared<ParamsSensorCamera>(); params->width = 640; params->height = 480; params->pinhole_model_raw << 321, 241, 321, 321; @@ -118,7 +118,7 @@ TEST(SensorCamera, create) TEST(SensorCamera, install) { Eigen::VectorXd extrinsics(7); extrinsics << 0,0,0, 0,0,0,1; - IntrinsicsCameraPtr params = std::make_shared<IntrinsicsCamera>(); + ParamsSensorCameraPtr params = std::make_shared<ParamsSensorCamera>(); params->width = 640; params->height = 480; params->pinhole_model_raw << 321, 241, 321, 321;