diff --git a/3rdparty/apriltag/CMakeLists.txt b/3rdparty/apriltag/CMakeLists.txt index 5191919cc1..45ef68ba88 100644 --- a/3rdparty/apriltag/CMakeLists.txt +++ b/3rdparty/apriltag/CMakeLists.txt @@ -63,7 +63,7 @@ endif() if(MSVC) if(BUILD_SHARED_LIBS) - vp_warnings_disable(CMAKE_CXX_FLAGS /wd4018 /wd4098 /wd4244 /wd4267 /wd4305 /wd4334 /wd4244 /wd4838 /wd4996 /wd6011 /wd6385 /wd6386 /wd6387 /wd6011 /wd26451) + vp_warnings_disable(CMAKE_CXX_FLAGS /wd4018 /wd4098 /wd4200 /wd4244 /wd4267 /wd4305 /wd4334 /wd4244 /wd4838 /wd4996 /wd6011 /wd6385 /wd6386 /wd6387 /wd6011 /wd26451) vp_set_source_file_compile_flag(common/matd.c /wd4244) vp_set_source_file_compile_flag(common/g2d.c /wd4244) vp_set_source_file_compile_flag(common/homography.c /wd4244) @@ -82,7 +82,7 @@ if(MSVC) vp_set_source_file_compile_flag(tag16h5.c /wd4996 /wd4244) vp_set_source_file_compile_flag(tag25h7.c /wd4996 /wd4244) vp_set_source_file_compile_flag(tag25h9.c /wd4996 /wd4244) - vp_set_source_file_compile_flag(tag36h10.c /wd4996 /wd42446) + vp_set_source_file_compile_flag(tag36h10.c /wd4996 /wd4244) vp_set_source_file_compile_flag(tag36h11.c /wd4996 /wd4244) vp_set_source_file_compile_flag(tagCircle21h7.c /wd4996 /wd4244) # disable optimization diff --git a/demo/wireframe-simulator/servoSimu4Points.cpp b/demo/wireframe-simulator/servoSimu4Points.cpp index f23fbcd7ad..6454bad548 100644 --- a/demo/wireframe-simulator/servoSimu4Points.cpp +++ b/demo/wireframe-simulator/servoSimu4Points.cpp @@ -420,7 +420,7 @@ int main(int argc, const char **argv) // Compute the position of the external view which is fixed in the // object frame - camoMf.build(0, 0.0, 1.5, 0, vpMath::rad(150), 0); + camoMf.buildFrom(0, 0.0, 1.5, 0, vpMath::rad(150), 0); camoMf = camoMf * (sim.get_fMo().inverse()); if (opt_plot) { diff --git a/demo/wireframe-simulator/servoSimuSphere.cpp b/demo/wireframe-simulator/servoSimuSphere.cpp index 4bb868c9e4..b03cfd06e3 100644 --- a/demo/wireframe-simulator/servoSimuSphere.cpp +++ b/demo/wireframe-simulator/servoSimuSphere.cpp @@ -427,9 +427,8 @@ int main(int argc, const char **argv) robot.setVelocity(vpRobot::CAMERA_FRAME, v); sim.setCameraPositionRelObj(cMo); - // Compute the position of the external view which is fixed in the - // object frame - camoMf.build(0, 0.0, 2.5, 0, vpMath::rad(150), 0); + // Compute the position of the external view which is fixed in the object frame + camoMf.buildFrom(0, 0.0, 2.5, 0, vpMath::rad(150), 0); camoMf = camoMf * (sim.get_fMo().inverse()); if (opt_plot) { diff --git a/doc/tutorial/rendering/tutorial-panda3d.dox b/doc/tutorial/rendering/tutorial-panda3d.dox index 66ab3a0941..187031498a 100644 --- a/doc/tutorial/rendering/tutorial-panda3d.dox +++ b/doc/tutorial/rendering/tutorial-panda3d.dox @@ -38,7 +38,7 @@ vpPanda3DBaseRenderer, which implements basic functions for a panda renderer. $ cd $VISP_WS/3rdparty/panda3d $ git clone https://github.com/panda3d/panda3d $ cd panda3d - $ python3 makepanda/makepanda.py --everything --installer --no-egl --no-gles --no-gles2 --no-opencv + $ python3 makepanda/makepanda.py --everything --installer --no-egl --no-gles --no-gles2 --no-opencv --threads $(nproc) \endcode At this point you can either: 1. install the produced Debian package (recommended) with diff --git a/doc/tutorial/tracking/tutorial-tracking-tt.dox b/doc/tutorial/tracking/tutorial-tracking-tt.dox index fcc787c9dc..19291e5a58 100644 --- a/doc/tutorial/tracking/tutorial-tracking-tt.dox +++ b/doc/tutorial/tracking/tutorial-tracking-tt.dox @@ -210,7 +210,7 @@ vpTemplateTracker::setIterationMax() function. In tutorial-template-tracker.cpp we use vpTemplateTrackerSSDInverseCompositional class that implements the "Sum of Square Differences" as similarity function. To use Mutual Information that is more robust to occlusion and lighting changes, the code needs to be modified, first introducing vpTemplateTrackerMIInverseCompositional header, -then instanciating the tracker, and finally setting the paramaters to speed up the MI tracker that is slower than +then instantiating the tracker, and finally setting the paramaters to speed up the MI tracker that is slower than the SSD one: - **Adding vpTemplateTrackerMIInverseCompositional header** consists in adding the following line at the beginning diff --git a/doc/tutorial/visual-servo/tutorial-simu-robot-pioneer.dox b/doc/tutorial/visual-servo/tutorial-simu-robot-pioneer.dox index 03024aab9e..3af6b510b2 100644 --- a/doc/tutorial/visual-servo/tutorial-simu-robot-pioneer.dox +++ b/doc/tutorial/visual-servo/tutorial-simu-robot-pioneer.dox @@ -143,7 +143,7 @@ frame. The desired position of the feature is set to (0,0). The depth of the point \c cdMo[2][3] is required to compute the feature position. \code - s_xd.build(0, 0, cdMo[2][3]); + s_xd.buildFrom(0, 0, cdMo[2][3]); \endcode Finally only the position of the feature along x is added to the task. @@ -167,12 +167,12 @@ Then, we get the current \c Z and desired \c Zd depth of the target. From these values, we are able to initialize the current depth feature: \code - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z/Zd)); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z/Zd)); \endcode and also the desired one: \code - s_Zd.build(0, 0, Zd, 0); + s_Zd.buildFrom(0, 0, Zd, 0); \endcode Finally, we add the feature to the task: @@ -204,7 +204,7 @@ Based on these new coordinates, we update the point visual feature \c s_x: and also the depth visual feature: \code Z = point.get_Z() ; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z/Zd)) ; + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z/Zd)) ; \endcode We also update the task with the values of the velocity twist matrix \c cVe and the robot jacobian \c eJe: diff --git a/example/calibration/calibrate-hand-eye.cpp b/example/calibration/calibrate-hand-eye.cpp index eca9831650..fe7a26e738 100644 --- a/example/calibration/calibrate-hand-eye.cpp +++ b/example/calibration/calibrate-hand-eye.cpp @@ -79,7 +79,7 @@ int main() erc[1] = vpMath::rad(-10); // -10 deg erc[2] = vpMath::rad(25); // 25 deg - eMc.build(etc, erc); + eMc.buildFrom(etc, erc); std::cout << "Simulated hand-eye transformation: eMc " << std::endl; std::cout << eMc << std::endl; std::cout << "Theta U rotation: " << vpMath::deg(erc[0]) << " " << vpMath::deg(erc[1]) << " " << vpMath::deg(erc[2]) @@ -90,8 +90,8 @@ int main() v_c = 0; if (i == 0) { // Initialize first poses - cMo[0].build(0, 0, 0.5, 0, 0, 0); // z=0.5 m - wMe[0].build(0, 0, 0, 0, 0, 0); // Id + cMo[0].buildFrom(0, 0, 0.5, 0, 0, 0); // z=0.5 m + wMe[0].buildFrom(0, 0, 0, 0, 0, 0); // Id } else if (i == 1) v_c[3] = M_PI / 8; @@ -171,4 +171,4 @@ int main() std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp b/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp index d1f3111b9e..8a9e2fce94 100644 --- a/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp +++ b/example/coin-simulator/simulateFourPoints2DCartesianCamVelocity.cpp @@ -226,10 +226,10 @@ static void *mainLoop(void *_simu) // Sets the desired position of the point vpFeaturePoint pd[4]; - pd[0].build(-0.1, -0.1, 1); - pd[1].build(0.1, -0.1, 1); - pd[2].build(0.1, 0.1, 1); - pd[3].build(-0.1, 0.1, 1); + pd[0].buildFrom(-0.1, -0.1, 1); + pd[1].buildFrom(0.1, -0.1, 1); + pd[2].buildFrom(0.1, 0.1, 1); + pd[3].buildFrom(-0.1, 0.1, 1); // Define the task // We want an eye-in-hand control law diff --git a/example/device/framegrabber/CMakeLists.txt b/example/device/framegrabber/CMakeLists.txt index 3d85fbe193..49f1f039e5 100644 --- a/example/device/framegrabber/CMakeLists.txt +++ b/example/device/framegrabber/CMakeLists.txt @@ -70,7 +70,6 @@ if(VISP_HAVE_REALSENSE OR VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-float-equal") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-ignored-qualifiers") - list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-inconsistent-missing-override") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-overloaded-virtual") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-pessimizing-move") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-reorder") @@ -79,7 +78,6 @@ if(VISP_HAVE_REALSENSE OR VISP_HAVE_REALSENSE2) list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-sign-conversion") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-function") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unused-parameter") - list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-unqualified-std-cast-call") list(APPEND CXX_FLAGS_MUTE_WARNINGS "-Wno-missing-field-initializers") visp_set_source_file_compile_flag(getRealSense2Info.cpp ${CXX_FLAGS_MUTE_WARNINGS}) diff --git a/example/device/framegrabber/readRealSenseData.cpp b/example/device/framegrabber/readRealSenseData.cpp index 24ba124a22..bd28d64066 100644 --- a/example/device/framegrabber/readRealSenseData.cpp +++ b/example/device/framegrabber/readRealSenseData.cpp @@ -165,6 +165,8 @@ bool getOptions(int argc, const char *argv[], std::string &input_directory, std: case 'z': read_npz = true; break; +#else + (void)read_npz; #endif case 'o': save_video = true; diff --git a/example/direct-visual-servoing/photometricMappingVisualServoing.cpp b/example/direct-visual-servoing/photometricMappingVisualServoing.cpp index 5f1a7cc047..e20fb7d829 100644 --- a/example/direct-visual-servoing/photometricMappingVisualServoing.cpp +++ b/example/direct-visual-servoing/photometricMappingVisualServoing.cpp @@ -399,7 +399,7 @@ int main(int argc, const char **argv) // camera desired position vpHomogeneousMatrix cMo; - cMo.build(0.0, 0, Z + 0.2, vpMath::rad(15), vpMath::rad(-5), vpMath::rad(5)); + cMo.buildFrom(0.0, 0, Z + 0.2, vpMath::rad(15), vpMath::rad(-5), vpMath::rad(5)); vpHomogeneousMatrix wMo; // Set to identity vpHomogeneousMatrix wMc; // Camera position in the world frame @@ -460,7 +460,7 @@ int main(int argc, const char **argv) luminanceI.init(I.getHeight(), I.getWidth(), Z); luminanceI.setCameraParameters(cam); vpFeatureLuminanceMapping sI(luminanceI, sMapping); - sI.build(I); + sI.buildFrom(I); sI.getMapping()->inverse(sI.get_s(), Irec); // desired visual feature built from the image @@ -468,7 +468,7 @@ int main(int argc, const char **argv) luminanceId.init(I.getHeight(), I.getWidth(), Z); luminanceId.setCameraParameters(cam); vpFeatureLuminanceMapping sId(luminanceId, sdMapping); - sId.build(Id); + sId.buildFrom(Id); // set a velocity control mode robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL); @@ -497,7 +497,7 @@ int main(int argc, const char **argv) vpImageTools::imageDifference(I, Id, Idiff); // Compute current visual features - sI.build(I); + sI.buildFrom(I); sI.getMapping()->inverse(sI.get_s(), Irec); if (iter > iterGN) { diff --git a/example/direct-visual-servoing/photometricVisualServoing.cpp b/example/direct-visual-servoing/photometricVisualServoing.cpp index 7ad27ed54a..8997ea2681 100644 --- a/example/direct-visual-servoing/photometricVisualServoing.cpp +++ b/example/direct-visual-servoing/photometricVisualServoing.cpp @@ -300,7 +300,7 @@ int main(int argc, const char **argv) // camera desired position vpHomogeneousMatrix cMo; - cMo.build(0, 0, 1.2, vpMath::rad(15), vpMath::rad(-5), vpMath::rad(20)); + cMo.buildFrom(0, 0, 1.2, vpMath::rad(15), vpMath::rad(-5), vpMath::rad(20)); vpHomogeneousMatrix wMo; // Set to identity vpHomogeneousMatrix wMc; // Camera position in the world frame @@ -356,13 +356,13 @@ int main(int argc, const char **argv) vpFeatureLuminance sI; sI.init(I.getHeight(), I.getWidth(), Z); sI.setCameraParameters(cam); - sI.build(I); + sI.buildFrom(I); // desired visual feature built from the image vpFeatureLuminance sId; sId.init(I.getHeight(), I.getWidth(), Z); sId.setCameraParameters(cam); - sId.build(Id); + sId.buildFrom(Id); // Create visual-servoing task vpServo servo; @@ -406,7 +406,7 @@ int main(int argc, const char **argv) } #endif // Compute current visual feature - sI.build(I); + sI.buildFrom(I); v = servo.computeControlLaw(); // camera velocity send to the robot diff --git a/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp b/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp index 3953b261cb..5d4cfefb3d 100644 --- a/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp +++ b/example/direct-visual-servoing/photometricVisualServoingWithoutVpServo.cpp @@ -301,7 +301,7 @@ int main(int argc, const char **argv) // camera desired position vpHomogeneousMatrix cMo; - cMo.build(0, 0, 1.2, vpMath::rad(15), vpMath::rad(-5), vpMath::rad(20)); + cMo.buildFrom(0, 0, 1.2, vpMath::rad(15), vpMath::rad(-5), vpMath::rad(20)); vpHomogeneousMatrix wMo; // Set to identity vpHomogeneousMatrix wMc; // Camera position in the world frame @@ -357,13 +357,13 @@ int main(int argc, const char **argv) vpFeatureLuminance sI; sI.init(I.getHeight(), I.getWidth(), Z); sI.setCameraParameters(cam); - sI.build(I); + sI.buildFrom(I); // desired visual feature built from the image vpFeatureLuminance sId; sId.init(I.getHeight(), I.getWidth(), Z); sId.setCameraParameters(cam); - sId.build(Id); + sId.buildFrom(Id); // Matrice d'interaction, Hessien, erreur,... vpMatrix Lsd; // matrice d'interaction a la position desiree @@ -435,7 +435,7 @@ int main(int argc, const char **argv) } #endif // Compute current visual feature - sI.build(I); + sI.buildFrom(I); // compute current error sI.error(sId, error); diff --git a/example/kalman/ukf-nonlinear-complex-example.cpp b/example/kalman/ukf-nonlinear-complex-example.cpp index fce3da31e6..d6daa6a0d1 100644 --- a/example/kalman/ukf-nonlinear-complex-example.cpp +++ b/example/kalman/ukf-nonlinear-complex-example.cpp @@ -74,6 +74,8 @@ * the interval \f$[- \pi ; \pi ]\f$ . */ +#include + // UKF includes #include #include diff --git a/example/manual/hello-world/CMake/HelloWorld.cpp b/example/manual/hello-world/CMake/HelloWorld.cpp index 5c09fbb119..704be20032 100644 --- a/example/manual/hello-world/CMake/HelloWorld.cpp +++ b/example/manual/hello-world/CMake/HelloWorld.cpp @@ -53,7 +53,7 @@ int main() vpRotationMatrix R(vpMath::rad(0.), vpMath::rad(180) + 100 * std::numeric_limits::epsilon(), 0.); // Extract the theta U angles from a rotation matrix - tu.build(R); + tu.buildFrom(R); // Since the rotation vector is 3 values column vector, the // transpose operation produce a row vector. diff --git a/example/math/exponentialMap.cpp b/example/math/exponentialMap.cpp index 4304e25ee2..26936bc2ec 100644 --- a/example/math/exponentialMap.cpp +++ b/example/math/exponentialMap.cpp @@ -66,7 +66,7 @@ int main() // Build a ThetaU rotation vector from a Rxyz vector vpThetaUVector tu; - tu.build(rxyz); + tu.buildFrom(rxyz); vpColVector v(6); // Velocity vector [t, thetaU]^t diff --git a/example/particle-filter/pf-nonlinear-complex-example.cpp b/example/particle-filter/pf-nonlinear-complex-example.cpp index 86ce9da936..bc6c30a0b4 100644 --- a/example/particle-filter/pf-nonlinear-complex-example.cpp +++ b/example/particle-filter/pf-nonlinear-complex-example.cpp @@ -469,7 +469,7 @@ class vpLandmarksGrid */ vpLandmarksGrid(const std::vector &landmarks, const double &distMaxAllowed) : m_landmarks(landmarks) - , m_nbLandmarks(landmarks.size()) + , m_nbLandmarks(static_cast(landmarks.size())) { double sigmaDistance = distMaxAllowed / 3.; double sigmaDistanceSquared = sigmaDistance * sigmaDistance; diff --git a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp index 0ff5f12aa5..d61d520644 100644 --- a/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cMcd_CamVelocity.cpp @@ -225,11 +225,11 @@ int main(int argc, const char **argv) // Build the 3D translation feature: ctc* vpFeatureTranslation t(vpFeatureTranslation::cMcd); - t.build(cMcd); + t.buildFrom(cMcd); // Build the 3D rotation feature: thetaU_cRc* vpFeatureThetaU tu(vpFeatureThetaU::cRcd); // current feature - tu.build(cMcd); + tu.buildFrom(cMcd); // Sets the desired rotation (always zero !) since s is the // rotation that the camera has to achieve. Here s* = (0, 0)^T @@ -269,8 +269,8 @@ int main(int argc, const char **argv) cMcd = cMo * cdMo.inverse(); // Update the current visual features - t.build(cMcd); - tu.build(cMcd); + t.buildFrom(cMcd); + tu.buildFrom(cMcd); // Compute the control law v = task.computeControlLaw(); @@ -307,4 +307,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp index 28f350cc43..e6358af205 100644 --- a/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimu3D_cdMc_CamVelocity.cpp @@ -226,8 +226,8 @@ int main(int argc, const char **argv) // Build the current visual features s = (c*tc, thetaU_c*Rc)^T vpFeatureTranslation t(vpFeatureTranslation::cdMc); vpFeatureThetaU tu(vpFeatureThetaU::cdRc); // current feature - t.build(cdMc); - tu.build(cdMc); + t.buildFrom(cdMc); + tu.buildFrom(cdMc); // Sets the desired rotation (always zero !) since s is the // rotation that the camera has to achieve. Here s* = (0, 0)^T @@ -267,8 +267,8 @@ int main(int argc, const char **argv) cdMc = cdMo * cMo.inverse(); // Update the current visual features - t.build(cdMc); - tu.build(cdMc); + t.buildFrom(cdMc); + tu.buildFrom(cdMc); // Compute the control law v = task.computeControlLaw(); @@ -303,4 +303,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp index c02062c1a5..0d2619286f 100644 --- a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocity.cpp @@ -192,10 +192,10 @@ int main(int argc, const char **argv) // sets the desired position of the point vpFeaturePoint pd[4]; - pd[0].build(-0.1, -0.1, 1); - pd[1].build(0.1, -0.1, 1); - pd[2].build(0.1, 0.1, 1); - pd[3].build(-0.1, 0.1, 1); + pd[0].buildFrom(-0.1, -0.1, 1); + pd[1].buildFrom(0.1, -0.1, 1); + pd[2].buildFrom(0.1, 0.1, 1); + pd[3].buildFrom(-0.1, 0.1, 1); // define the task // - we want an eye-in-hand control law @@ -247,10 +247,10 @@ int main(int argc, const char **argv) } // since vpServo::MEAN interaction matrix is used, we need also to // update the desired features at each iteration - pd[0].build(-0.1, -0.1, 1); - pd[1].build(0.1, -0.1, 1); - pd[2].build(0.1, 0.1, 1); - pd[3].build(-0.1, 0.1, 1); + pd[0].buildFrom(-0.1, -0.1, 1); + pd[1].buildFrom(0.1, -0.1, 1); + pd[2].buildFrom(0.1, 0.1, 1); + pd[3].buildFrom(-0.1, 0.1, 1); // compute the control law ") ; v = task.computeControlLaw(); @@ -275,4 +275,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp index c544164ae6..d9e0f77937 100644 --- a/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp +++ b/example/robot-simulator/camera/servoSimuFourPoints2DCamVelocityDisplay.cpp @@ -255,10 +255,10 @@ int main(int argc, const char **argv) // sets the desired position of the feature point s* vpFeaturePoint pd[4]; - pd[0].build(-0.1, -0.1, 1); - pd[1].build(0.1, -0.1, 1); - pd[2].build(0.1, 0.1, 1); - pd[3].build(-0.1, 0.1, 1); + pd[0].buildFrom(-0.1, -0.1, 1); + pd[1].buildFrom(0.1, -0.1, 1); + pd[2].buildFrom(0.1, 0.1, 1); + pd[3].buildFrom(-0.1, 0.1, 1); // define the task // - we want an eye-in-hand control law @@ -310,10 +310,10 @@ int main(int argc, const char **argv) } // since vpServo::MEAN interaction matrix is used, we need also to // update the desired features at each iteration - pd[0].build(-0.1, -0.1, 1); - pd[1].build(0.1, -0.1, 1); - pd[2].build(0.1, 0.1, 1); - pd[3].build(-0.1, 0.1, 1); + pd[0].buildFrom(-0.1, -0.1, 1); + pd[1].buildFrom(0.1, -0.1, 1); + pd[2].buildFrom(0.1, 0.1, 1); + pd[3].buildFrom(-0.1, 0.1, 1); if (opt_display) { vpDisplay::display(Iint); diff --git a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp index ea5743dbcf..6a32abf4a2 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity1.cpp @@ -167,7 +167,7 @@ int main(int argc, const char **argv) // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); // build(x,y,Z) ; + pd.buildFrom(0, 0, 1); // buildFrom(x,y,Z) ; // define the task // - we want an eye-in-hand control law @@ -223,4 +223,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp index c91d12493d..9305938829 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity2.cpp @@ -183,7 +183,7 @@ int main(int argc, const char **argv) // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // define the task // - we want an eye-in-hand control law @@ -228,7 +228,7 @@ int main(int argc, const char **argv) // new point position point.track(cMo); vpFeatureBuilder::create(p, point); // retrieve x,y and Z of the vpPoint structure - pd.build(0, 0, 1); // Since vpServo::MEAN interaction matrix is + pd.buildFrom(0, 0, 1); // Since vpServo::MEAN interaction matrix is // used, we need to update the desired feature at // each iteration @@ -255,4 +255,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp index dd6f6f0aa4..0d7ef00670 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DCamVelocity3.cpp @@ -182,7 +182,7 @@ int main(int argc, const char **argv) // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); // build(x,y,Z) ; + pd.buildFrom(0, 0, 1); // buildFrom(x,y,Z) ; // define the task // - we want an eye-in-hand control law @@ -251,4 +251,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp index a40dcae8d8..e57aa40910 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity1.cpp @@ -204,7 +204,7 @@ int main(int argc, const char **argv) cdMc = cdMo * cMo.inverse(); vpFeatureThetaU tu(vpFeatureThetaU::cdRc); - tu.build(cdMc); + tu.buildFrom(cdMc); // sets the desired rotation (always zero !) // since s is the rotation that the camera has to achieve @@ -242,7 +242,7 @@ int main(int argc, const char **argv) vpFeatureBuilder::create(Z, point); cdMc = cdMo * cMo.inverse(); - tu.build(cdMc); + tu.buildFrom(cdMc); // compute the control law v = task.computeControlLaw(); @@ -267,4 +267,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp index bb010efd48..7adad57bf5 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity2.cpp @@ -266,7 +266,7 @@ int main(int argc, const char **argv) // from this displacement, we extract the rotation cdRc represented by // the angle theta and the rotation axis u vpFeatureThetaU tu(vpFeatureThetaU::cdRc); - tu.build(cdMc); + tu.buildFrom(cdMc); // This visual has to be regulated to zero // sets the desired rotation (always zero !) @@ -318,7 +318,7 @@ int main(int argc, const char **argv) vpFeatureBuilder::create(p, point); cdMc = cdMo * cMo.inverse(); - tu.build(cdMc); + tu.buildFrom(cdMc); // there is no feature for logZ, we explicitly build // the related interaction matrix") ; @@ -356,4 +356,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp index 121ae424df..442e1dac47 100644 --- a/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp +++ b/example/robot-simulator/camera/servoSimuPoint2DhalfCamVelocity3.cpp @@ -249,10 +249,10 @@ int main(int argc, const char **argv) // from this displacement, we extract the rotation cdRc represented by // the angle theta and the rotation axis u vpFeatureThetaU tuz(vpFeatureThetaU::cdRc); - tuz.build(cdMc); + tuz.buildFrom(cdMc); // And the translations vpFeatureTranslation t(vpFeatureTranslation::cdMc); - t.build(cdMc); + t.buildFrom(cdMc); // This visual has to be regulated to zero @@ -306,8 +306,8 @@ int main(int argc, const char **argv) vpFeatureBuilder::create(p, P); cdMc = cdMo * cMo.inverse(); - tuz.build(cdMc); - t.build(cdMc); + tuz.buildFrom(cdMc); + t.buildFrom(cdMc); // compute the control law: v = -lambda L^+(s-sd) v = task.computeControlLaw(); @@ -334,4 +334,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp b/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp index b5b6a2876f..3468b82643 100644 --- a/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuPoint3DCamVelocity.cpp @@ -173,7 +173,7 @@ int main(int argc, const char **argv) std::cout << "Point coordinates in the camera frame: " << point.cP.t(); vpFeaturePoint3D p; - p.build(point); + p.buildFrom(point); // sets the desired position of the point vpFeaturePoint3D pd; @@ -207,7 +207,7 @@ int main(int argc, const char **argv) // new point position point.track(cMo); - p.build(point); + p.buildFrom(point); // std::cout << p.cP.t() ; // std::cout << (p.get_s()).t() ; @@ -233,4 +233,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp b/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp index f0df9b5be6..5baf5b18f3 100644 --- a/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp +++ b/example/robot-simulator/camera/servoSimuThetaUCamVelocity.cpp @@ -172,7 +172,7 @@ int main(int argc, const char **argv) vpHomogeneousMatrix cdMc; cdMc = cdMo * cMo.inverse(); vpFeatureThetaU tu(vpFeatureThetaU::cdRc); - tu.build(cdMc); + tu.buildFrom(cdMc); // define the task // - we want an eye-in-hand control law @@ -201,7 +201,7 @@ int main(int argc, const char **argv) // new rotation to achieve cdMc = cdMo * cMo.inverse(); - tu.build(cdMc); + tu.buildFrom(cdMc); // compute the control law v = task.computeControlLaw(); @@ -226,4 +226,4 @@ int main(int argc, const char **argv) std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl; return EXIT_SUCCESS; #endif - } +} diff --git a/example/servo-afma4/servoAfma4Point2DArtVelocity.cpp b/example/servo-afma4/servoAfma4Point2DArtVelocity.cpp index 96a227240e..a81a28b3fd 100644 --- a/example/servo-afma4/servoAfma4Point2DArtVelocity.cpp +++ b/example/servo-afma4/servoAfma4Point2DArtVelocity.cpp @@ -182,7 +182,7 @@ int main() p.set_Z(1); vpTRACE("sets the desired position of the visual feature "); vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); vpTRACE("define the task"); vpTRACE("\t we want an eye-in-hand control law"); diff --git a/example/servo-afma4/servoAfma4Point2DCamVelocity.cpp b/example/servo-afma4/servoAfma4Point2DCamVelocity.cpp index 78df661550..ab673b9a83 100644 --- a/example/servo-afma4/servoAfma4Point2DCamVelocity.cpp +++ b/example/servo-afma4/servoAfma4Point2DCamVelocity.cpp @@ -173,7 +173,7 @@ int main() vpTRACE("sets the desired position of the visual feature "); vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); vpTRACE("define the task"); vpTRACE("\t we want an eye-in-hand control law"); diff --git a/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp b/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp index 728299e9d1..962b768280 100644 --- a/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp +++ b/example/servo-afma4/servoAfma4Point2DCamVelocityKalman.cpp @@ -308,7 +308,7 @@ int main(int argc, const char **argv) // Sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-afma6/servoAfma62DhalfCamVelocity.cpp b/example/servo-afma6/servoAfma62DhalfCamVelocity.cpp index 1576859d40..60b23db2bb 100644 --- a/example/servo-afma6/servoAfma62DhalfCamVelocity.cpp +++ b/example/servo-afma6/servoAfma62DhalfCamVelocity.cpp @@ -207,14 +207,14 @@ int main() // The second feature is the depth of the current square center relative // to the depth of the desired square center. vpFeatureDepth s_logZ; - s_logZ.build(pointc.get_x(), pointc.get_y(), pointc.get_Z(), log(pointc.get_Z() / pointcd.get_Z())); + s_logZ.buildFrom(pointc.get_x(), pointc.get_y(), pointc.get_Z(), log(pointc.get_Z() / pointcd.get_Z())); // The last three features are the rotations thetau between the current // pose and the desired pose. vpHomogeneousMatrix cd_M_c; cd_M_c = cd_M_o * c_M_o.inverse(); vpFeatureThetaU s_tu(vpFeatureThetaU::cdRc); - s_tu.build(cd_M_c); + s_tu.buildFrom(cd_M_c); // Define the task // - we want an eye-in-hand control law @@ -284,11 +284,11 @@ int main() } // Update the second feature - s_logZ.build(pointc.get_x(), pointc.get_y(), pointc.get_Z(), log(pointc.get_Z() / pointcd.get_Z())); + s_logZ.buildFrom(pointc.get_x(), pointc.get_y(), pointc.get_Z(), log(pointc.get_Z() / pointcd.get_Z())); // Update the last three features cd_M_c = cd_M_o * c_M_o.inverse(); - s_tu.build(cd_M_c); + s_tu.buildFrom(cd_M_c); vpColVector v_c = task.computeControlLaw(); diff --git a/example/servo-afma6/servoAfma6AprilTagIBVS.cpp b/example/servo-afma6/servoAfma6AprilTagIBVS.cpp index 196730dd9d..f9cbe2dce2 100644 --- a/example/servo-afma6/servoAfma6AprilTagIBVS.cpp +++ b/example/servo-afma6/servoAfma6AprilTagIBVS.cpp @@ -341,7 +341,7 @@ int main(int argc, char **argv) if (first_time) { // Introduce security wrt tag positioning in order to avoid PI rotation std::vector v_o_M_o(2), v_cd_M_c(2); - v_o_M_o[1].build(0, 0, 0, 0, 0, M_PI); + v_o_M_o[1].buildFrom(0, 0, 0, 0, 0, M_PI); for (size_t i = 0; i < 2; ++i) { v_cd_M_c[i] = cd_M_o * v_o_M_o[i] * c_M_o.inverse(); } diff --git a/example/servo-afma6/servoAfma6AprilTagPBVS.cpp b/example/servo-afma6/servoAfma6AprilTagPBVS.cpp index 04705ffb63..957ec1df3c 100644 --- a/example/servo-afma6/servoAfma6AprilTagPBVS.cpp +++ b/example/servo-afma6/servoAfma6AprilTagPBVS.cpp @@ -249,8 +249,8 @@ int main(int argc, char **argv) // Create current visual features vpFeatureTranslation s_t(vpFeatureTranslation::cdMc); vpFeatureThetaU s_tu(vpFeatureThetaU::cdRc); - s_t.build(cd_M_c); - s_tu.build(cd_M_c); + s_t.buildFrom(cd_M_c); + s_tu.buildFrom(cd_M_c); // Create desired visual features vpFeatureTranslation s_t_d(vpFeatureTranslation::cdMc); @@ -329,7 +329,7 @@ int main(int argc, char **argv) if (first_time) { // Introduce security wrt tag positioning in order to avoid PI rotation std::vector v_o_M_o(2), v_cd_M_c(2); - v_o_M_o[1].build(0, 0, 0, 0, 0, M_PI); + v_o_M_o[1].buildFrom(0, 0, 0, 0, 0, M_PI); for (size_t i = 0; i < 2; ++i) { v_cd_M_c[i] = cd_M_o * v_o_M_o[i] * c_M_o.inverse(); } @@ -344,8 +344,8 @@ int main(int argc, char **argv) // Update current visual features cd_M_c = cd_M_o * o_M_o * c_M_o.inverse(); - s_t.build(cd_M_c); - s_tu.build(cd_M_c); + s_t.buildFrom(cd_M_c); + s_tu.buildFrom(cd_M_c); if (opt_task_sequencing) { if (!servo_started) { diff --git a/example/servo-afma6/servoAfma6Ellipse2DCamVelocity.cpp b/example/servo-afma6/servoAfma6Ellipse2DCamVelocity.cpp index 1a9e31d048..adc2c86627 100644 --- a/example/servo-afma6/servoAfma6Ellipse2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6Ellipse2DCamVelocity.cpp @@ -158,7 +158,7 @@ int main() f >> n11; f >> n02; f.close(); - cd.build(x, y, n20, n11, n02); + cd.buildFrom(x, y, n20, n11, n02); cd.setABC(0, 0, 10); task.setServo(vpServo::EYEINHAND_CAMERA); diff --git a/example/servo-afma6/servoAfma6FourPoints2DArtVelocity.cpp b/example/servo-afma6/servoAfma6FourPoints2DArtVelocity.cpp index 0d32040fcc..e9f72b60ec 100644 --- a/example/servo-afma6/servoAfma6FourPoints2DArtVelocity.cpp +++ b/example/servo-afma6/servoAfma6FourPoints2DArtVelocity.cpp @@ -161,10 +161,10 @@ int main() // Sets the desired position of the visual feature vpFeaturePoint s_d[4]; - s_d[0].build(-L/D, -L/D, D); - s_d[1].build(+L/D, -L/D, D); - s_d[2].build(+L/D, +L/D, D); - s_d[3].build(-L/D, +L/D, D); + s_d[0].buildFrom(-L/D, -L/D, D); + s_d[1].buildFrom(+L/D, -L/D, D); + s_d[2].buildFrom(+L/D, +L/D, D); + s_d[3].buildFrom(-L/D, +L/D, D); // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur.cpp b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur.cpp index 5a642b9c67..0961116f79 100644 --- a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur.cpp +++ b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur.cpp @@ -209,7 +209,7 @@ int main() vpTranslationVector c_t_o(0, 0, 0.5); // tz = 0.5 meter vpRxyzVector c_r_o(vpMath::rad(0), vpMath::rad(0), vpMath::rad(0)); // No rotations vpRotationMatrix c_R_o(c_r_o); // Build the rotation matrix - c_M_o.build(c_t_o, c_R_o); // Build the homogeneous matrix + c_M_o.buildFrom(c_t_o, c_R_o); // Build the homogeneous matrix // Sets the desired position of the 2D visual feature std::vector s_d(4); diff --git a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur_integrator.cpp b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur_integrator.cpp index f79758e659..743a42dea3 100644 --- a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur_integrator.cpp +++ b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_cur_integrator.cpp @@ -213,7 +213,7 @@ int main() vpTranslationVector c_t_o(0, 0, 0.5); // tz = 0.5 meter vpRxyzVector c_r_o(vpMath::rad(0), vpMath::rad(-20), vpMath::rad(0)); // No rotations vpRotationMatrix c_R_o(c_r_o); // Build the rotation matrix - c_M_o.build(c_t_o, c_R_o); // Build the homogeneous matrix + c_M_o.buildFrom(c_t_o, c_R_o); // Build the homogeneous matrix // Sets the desired position of the 2D visual feature std::vector s_d(4); diff --git a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_des.cpp b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_des.cpp index 8143fc34b1..b9c3d5e066 100644 --- a/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_des.cpp +++ b/example/servo-afma6/servoAfma6FourPoints2DCamVelocityLs_des.cpp @@ -170,7 +170,7 @@ int main() vpTranslationVector c_t_o(0, 0, 0.5); // tz = 0.5 meter vpRxyzVector c_r_o(vpMath::rad(0), vpMath::rad(0), vpMath::rad(0)); // No rotations vpRotationMatrix c_R_o(c_r_o); // Build the rotation matrix - c_M_o.build(c_t_o, c_R_o); // Build the homogeneous matrix + c_M_o.buildFrom(c_t_o, c_R_o); // Build the homogeneous matrix // Sets the desired position of the 2D visual feature std::vector s_d(4); diff --git a/example/servo-afma6/servoAfma6MegaposePBVS.cpp b/example/servo-afma6/servoAfma6MegaposePBVS.cpp index 307c4df74e..fea75c98f8 100644 --- a/example/servo-afma6/servoAfma6MegaposePBVS.cpp +++ b/example/servo-afma6/servoAfma6MegaposePBVS.cpp @@ -244,8 +244,8 @@ int main(int argc, const char *argv[]) vpHomogeneousMatrix cdTc = cdTo * cTo.inverse(); vpFeatureTranslation t(vpFeatureTranslation::cdMc); vpFeatureThetaU tu(vpFeatureThetaU::cdRc); - t.build(cdTc); - tu.build(cdTc); + t.buildFrom(cdTc); + tu.buildFrom(cdTc); vpFeatureTranslation td(vpFeatureTranslation::cdMc); vpFeatureThetaU tud(vpFeatureThetaU::cdRc); @@ -323,8 +323,8 @@ int main(int argc, const char *argv[]) // Update visual features cdTc = cdTo * cTo.inverse(); - t.build(cdTc); - tu.build(cdTc); + t.buildFrom(cdTc); + tu.buildFrom(cdTc); v = task.computeControlLaw(); velocities.push_back(v); diff --git a/example/servo-afma6/servoAfma6Point2DArtVelocity.cpp b/example/servo-afma6/servoAfma6Point2DArtVelocity.cpp index d2684518a5..5c2d04846c 100644 --- a/example/servo-afma6/servoAfma6Point2DArtVelocity.cpp +++ b/example/servo-afma6/servoAfma6Point2DArtVelocity.cpp @@ -148,7 +148,7 @@ int main() // Sets the desired position of the visual feature vpFeaturePoint s_d; - s_d.build(0, 0, 1); // Here we consider the center of the image (x=y=0 and Z=1 meter) + s_d.buildFrom(0, 0, 1); // Here we consider the center of the image (x=y=0 and Z=1 meter) // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-afma6/servoAfma6Point2DCamVelocity.cpp b/example/servo-afma6/servoAfma6Point2DCamVelocity.cpp index a073de700c..2144651c04 100644 --- a/example/servo-afma6/servoAfma6Point2DCamVelocity.cpp +++ b/example/servo-afma6/servoAfma6Point2DCamVelocity.cpp @@ -149,7 +149,7 @@ int main() // Sets the desired position of the visual feature vpFeaturePoint s_d; - s_d.build(0, 0, 1); // Here we consider the center of the image (x=y=0 and Z=1 meter) + s_d.buildFrom(0, 0, 1); // Here we consider the center of the image (x=y=0 and Z=1 meter) // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp b/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp index 442263f789..6e5c381225 100644 --- a/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp +++ b/example/servo-biclops/servoBiclopsPoint2DArtVelocity.cpp @@ -250,7 +250,7 @@ int main(int argc, const char **argv) vpFeaturePoint p, pd; // Sets the desired position of the visual feature // Here we set Z desired to 1 meter, and (x,y)=(0,0) to center the tag in the image - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-flir-ptu/servoFlirPtuIBVS.cpp b/example/servo-flir-ptu/servoFlirPtuIBVS.cpp index f6145229f5..1cb9981f3b 100644 --- a/example/servo-flir-ptu/servoFlirPtuIBVS.cpp +++ b/example/servo-flir-ptu/servoFlirPtuIBVS.cpp @@ -278,7 +278,7 @@ int main(int argc, char **argv) if (!opt_extrinsic.empty()) { vpPoseVector ePc; ePc.loadYAML(opt_extrinsic, ePc); - eMc.build(ePc); + eMc.buildFrom(ePc); } else { std::cout << "***************************************************************" << std::endl; diff --git a/example/servo-franka/servoFrankaIBVS.cpp b/example/servo-franka/servoFrankaIBVS.cpp index b255252a3d..6b89eaf987 100644 --- a/example/servo-franka/servoFrankaIBVS.cpp +++ b/example/servo-franka/servoFrankaIBVS.cpp @@ -305,7 +305,7 @@ int main(int argc, char **argv) if (first_time) { // Introduce security wrt tag positioning in order to avoid PI rotation std::vector v_oMo(2), v_cdMc(2); - v_oMo[1].build(0, 0, 0, 0, 0, M_PI); + v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI); for (size_t i = 0; i < 2; i++) { v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse(); } diff --git a/example/servo-franka/servoFrankaPBVS.cpp b/example/servo-franka/servoFrankaPBVS.cpp index 2f79bd7f74..1594db60cc 100644 --- a/example/servo-franka/servoFrankaPBVS.cpp +++ b/example/servo-franka/servoFrankaPBVS.cpp @@ -218,8 +218,8 @@ int main(int argc, char **argv) cdMc = cdMo * cMo.inverse(); vpFeatureTranslation t(vpFeatureTranslation::cdMc); vpFeatureThetaU tu(vpFeatureThetaU::cdRc); - t.build(cdMc); - tu.build(cdMc); + t.buildFrom(cdMc); + tu.buildFrom(cdMc); vpFeatureTranslation td(vpFeatureTranslation::cdMc); vpFeatureThetaU tud(vpFeatureThetaU::cdRc); @@ -297,7 +297,7 @@ int main(int argc, char **argv) if (first_time) { // Introduce security wrt tag positioning in order to avoid PI rotation std::vector v_oMo(2), v_cdMc(2); - v_oMo[1].build(0, 0, 0, 0, 0, M_PI); + v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI); for (size_t i = 0; i < 2; i++) { v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse(); } @@ -312,8 +312,8 @@ int main(int argc, char **argv) // Update visual features cdMc = cdMo * oMo * cMo.inverse(); - t.build(cdMc); - tu.build(cdMc); + t.buildFrom(cdMc); + tu.buildFrom(cdMc); if (opt_task_sequencing) { if (!servo_started) { diff --git a/example/servo-pioneer/servoPioneerPoint2DDepth.cpp b/example/servo-pioneer/servoPioneerPoint2DDepth.cpp index d6427e9ed9..4e4b13a145 100644 --- a/example/servo-pioneer/servoPioneerPoint2DDepth.cpp +++ b/example/servo-pioneer/servoPioneerPoint2DDepth.cpp @@ -232,7 +232,7 @@ int main(int argc, char **argv) vpFeatureBuilder::create(s_x, cam, dot); // Create the desired x* visual feature - s_xd.build(0, 0, depth); + s_xd.buildFrom(0, 0, depth); // Add the feature task.addFeature(s_x, s_xd); @@ -250,9 +250,9 @@ int main(int argc, char **argv) Zd = Z; std::cout << "Z " << Z << std::endl; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, 0); // log(Z/Z*) = 0 that's why the last parameter is 0 - s_Zd.build(s_x.get_x(), s_x.get_y(), Zd, + s_Zd.buildFrom(s_x.get_x(), s_x.get_y(), Zd, 0); // log(Z/Z*) = 0 that's why the last parameter is 0 // Add the feature @@ -280,7 +280,7 @@ int main(int argc, char **argv) // the interaction matrix surface = 1. / sqrt(dot.m00 / (cam.get_px() * cam.get_py())); Z = coef * surface; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); robot.get_cVe(cVe); task.set_cVe(cVe); diff --git a/example/servo-pioneer/servoPioneerPoint2DDepthWithoutVpServo.cpp b/example/servo-pioneer/servoPioneerPoint2DDepthWithoutVpServo.cpp index 0cd8ac0d8f..40bd30b641 100644 --- a/example/servo-pioneer/servoPioneerPoint2DDepthWithoutVpServo.cpp +++ b/example/servo-pioneer/servoPioneerPoint2DDepthWithoutVpServo.cpp @@ -215,7 +215,7 @@ int main(int argc, char **argv) vpFeatureBuilder::create(s_x, cam, dot); // Create the desired x* visual feature - s_xd.build(0, 0, depth); + s_xd.buildFrom(0, 0, depth); vpMatrix L_x = s_xd.interaction(vpFeaturePoint::selectX()); // Create the current log(Z/Z*) visual feature @@ -229,7 +229,7 @@ int main(int argc, char **argv) // Desired depth Z* of the blob. This depth is learned and equal to the // initial depth Zd = Z; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, 0); // log(Z/Z*) = 0 that's why the last parameter is 0 vpMatrix L_Z = s_Z.interaction(); @@ -245,7 +245,7 @@ int main(int argc, char **argv) vpColVector v; // vz, wx vpFeatureDepth s_Zd; - s_Zd.build(0, 0, 1, 0); // The value of s* is 0 with Z=1 meter. + s_Zd.buildFrom(0, 0, 1, 0); // The value of s* is 0 with Z=1 meter. while (1) { // Acquire a new image @@ -267,7 +267,7 @@ int main(int argc, char **argv) // the intection matrix surface = 1. / sqrt(dot.m00 / (cam.get_px() * cam.get_py())); Z = coef * surface; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); L_Z = s_Z.interaction(); // Update the global interaction matrix diff --git a/example/servo-pololu-ptu/servoPololuPtuPoint2DJointVelocity.cpp b/example/servo-pololu-ptu/servoPololuPtuPoint2DJointVelocity.cpp index af6f443a9d..b69b4b0dfc 100644 --- a/example/servo-pololu-ptu/servoPololuPtuPoint2DJointVelocity.cpp +++ b/example/servo-pololu-ptu/servoPololuPtuPoint2DJointVelocity.cpp @@ -223,7 +223,7 @@ int main(int argc, const char **argv) vpFeaturePoint p, pd; // Sets the desired position of the visual feature // Here we set Z desired to 1 meter, and (x,y)=(0,0) to center the tag in the image - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp index a10d201ba4..94d4003114 100644 --- a/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp +++ b/example/servo-ptu46/servoPtu46Point2DArtVelocity.cpp @@ -174,7 +174,7 @@ int main() p.set_Z(1); vpTRACE("sets the desired position of the visual feature "); vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); vpTRACE("define the task"); vpTRACE("\t we want an eye-in-hand control law"); diff --git a/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp b/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp index bc347cf85b..2a94b25689 100644 --- a/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp +++ b/example/servo-universal-robots/servoUniversalRobotsIBVS.cpp @@ -321,7 +321,7 @@ int main(int argc, char **argv) if (first_time) { // Introduce security wrt tag positioning in order to avoid PI rotation std::vector v_oMo(2), v_cdMc(2); - v_oMo[1].build(0, 0, 0, 0, 0, M_PI); + v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI); for (size_t i = 0; i < 2; i++) { v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse(); } diff --git a/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp b/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp index 7205eee427..0af04753a1 100644 --- a/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp +++ b/example/servo-universal-robots/servoUniversalRobotsPBVS.cpp @@ -234,8 +234,8 @@ int main(int argc, char **argv) cdMc = cdMo * cMo.inverse(); vpFeatureTranslation t(vpFeatureTranslation::cdMc); vpFeatureThetaU tu(vpFeatureThetaU::cdRc); - t.build(cdMc); - tu.build(cdMc); + t.buildFrom(cdMc); + tu.buibuildFromld(cdMc); vpFeatureTranslation td(vpFeatureTranslation::cdMc); vpFeatureThetaU tud(vpFeatureThetaU::cdRc); @@ -313,7 +313,7 @@ int main(int argc, char **argv) if (first_time) { // Introduce security wrt tag positioning in order to avoid PI rotation std::vector v_oMo(2), v_cdMc(2); - v_oMo[1].build(0, 0, 0, 0, 0, M_PI); + v_oMo[1].buildFrom(0, 0, 0, 0, 0, M_PI); for (size_t i = 0; i < 2; i++) { v_cdMc[i] = cdMo * v_oMo[i] * cMo.inverse(); } @@ -328,8 +328,8 @@ int main(int argc, char **argv) // Update visual features cdMc = cdMo * oMo * cMo.inverse(); - t.build(cdMc); - tu.build(cdMc); + t.buildFrom(cdMc); + tu.buildFrom(cdMc); if (opt_task_sequencing) { if (!servo_started) { diff --git a/example/servo-viper650/servoViper650Point2DCamVelocity.cpp b/example/servo-viper650/servoViper650Point2DCamVelocity.cpp index 002e2aa488..c104479d1e 100644 --- a/example/servo-viper650/servoViper650Point2DCamVelocity.cpp +++ b/example/servo-viper650/servoViper650Point2DCamVelocity.cpp @@ -159,7 +159,7 @@ int main() // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // define the task // - we want an eye-in-hand control law diff --git a/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_cur.cpp b/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_cur.cpp index f687e552df..551fbab587 100644 --- a/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_cur.cpp +++ b/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_cur.cpp @@ -236,7 +236,7 @@ int main() vpTranslationVector cto(0, 0, 0.5); // tz = 0.5 meter vpRxyzVector cro(vpMath::rad(0), vpMath::rad(10), vpMath::rad(20)); vpRotationMatrix cRo(cro); // Build the rotation matrix - cMo.build(cto, cRo); // Build the homogeneous matrix + cMo.buildFrom(cto, cRo); // Build the homogeneous matrix // Sets the desired position of the 2D visual feature vpFeaturePoint pd[4]; diff --git a/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_des.cpp b/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_des.cpp index 6878b007ce..972fbdca0e 100644 --- a/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_des.cpp +++ b/example/servo-viper850/servoViper850FourPoints2DArtVelocityLs_des.cpp @@ -187,10 +187,10 @@ int main() // sets the desired position of the visual feature vpFeaturePoint pd[4]; - pd[0].build(-L, -L, D); - pd[1].build(L, -L, D); - pd[2].build(L, L, D); - pd[3].build(-L, L, D); + pd[0].buildFrom(-L, -L, D); + pd[1].buildFrom(L, -L, D); + pd[2].buildFrom(L, L, D); + pd[3].buildFrom(-L, L, D); // We want to see a point on a point std::cout << std::endl; diff --git a/example/servo-viper850/servoViper850FourPoints2DCamVelocityLs_cur.cpp b/example/servo-viper850/servoViper850FourPoints2DCamVelocityLs_cur.cpp index 2bf8f4222f..513dc00f10 100644 --- a/example/servo-viper850/servoViper850FourPoints2DCamVelocityLs_cur.cpp +++ b/example/servo-viper850/servoViper850FourPoints2DCamVelocityLs_cur.cpp @@ -237,7 +237,7 @@ int main() vpTranslationVector cto(0, 0, 0.5); // tz = 0.5 meter vpRxyzVector cro(vpMath::rad(10), vpMath::rad(30), vpMath::rad(20)); vpRotationMatrix cRo(cro); // Build the rotation matrix - cMo.build(cto, cRo); // Build the homogeneous matrix + cMo.buildFrom(cto, cRo); // Build the homogeneous matrix // Sets the desired position of the 2D visual feature vpFeaturePoint pd[4]; diff --git a/example/servo-viper850/servoViper850FourPointsKinect.cpp b/example/servo-viper850/servoViper850FourPointsKinect.cpp index 2195b9fce8..c827064ee2 100644 --- a/example/servo-viper850/servoViper850FourPointsKinect.cpp +++ b/example/servo-viper850/servoViper850FourPointsKinect.cpp @@ -248,7 +248,7 @@ int main() vpTranslationVector cto(0, 0, 0.5); // tz = 0.5 meter vpRxyzVector cro(vpMath::rad(0), vpMath::rad(0), vpMath::rad(0)); vpRotationMatrix cRo(cro); // Build the rotation matrix - cMo.build(cto, cRo); // Build the homogeneous matrix + cMo.buildFrom(cto, cRo); // Build the homogeneous matrix // Sets the desired position of the 2D visual feature vpFeaturePoint pd[4]; diff --git a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp index 701a63b87d..8b09ff9276 100644 --- a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp +++ b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp @@ -222,7 +222,7 @@ int main() p.set_Z(1); // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp index abba0b997a..0772cb258f 100644 --- a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp +++ b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp @@ -203,7 +203,7 @@ int main() p.set_Z(1); // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-large.cpp b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-large.cpp index 1a341d4285..44ee7a6d23 100644 --- a/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-large.cpp +++ b/example/servo-viper850/servoViper850Point2DArtVelocity-jointAvoidance-large.cpp @@ -185,7 +185,7 @@ int main() p.set_Z(1); // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // Define the task // - we want an eye-in-hand control law diff --git a/example/servo-viper850/servoViper850Point2DArtVelocity.cpp b/example/servo-viper850/servoViper850Point2DArtVelocity.cpp index 5ced809e38..d2c7c19f74 100644 --- a/example/servo-viper850/servoViper850Point2DArtVelocity.cpp +++ b/example/servo-viper850/servoViper850Point2DArtVelocity.cpp @@ -169,7 +169,7 @@ int main() p.set_Z(1); vpTRACE("sets the desired position of the visual feature "); vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); vpTRACE("define the task"); vpTRACE("\t we want an eye-in-hand control law"); diff --git a/example/servo-viper850/servoViper850Point2DCamVelocity.cpp b/example/servo-viper850/servoViper850Point2DCamVelocity.cpp index 15c39c204f..a0fdd70146 100644 --- a/example/servo-viper850/servoViper850Point2DCamVelocity.cpp +++ b/example/servo-viper850/servoViper850Point2DCamVelocity.cpp @@ -169,7 +169,7 @@ int main() // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // define the task // - we want an eye-in-hand control law diff --git a/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp b/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp index 44bff1775c..109fc83977 100644 --- a/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp +++ b/example/servo-viper850/servoViper850Point2DCamVelocityKalman.cpp @@ -212,7 +212,7 @@ int main() // sets the desired position of the visual feature vpFeaturePoint pd; - pd.build(0, 0, 1); + pd.buildFrom(0, 0, 1); // define the task // - we want an eye-in-hand control law diff --git a/example/tracking/mbtEdgeKltTracking.cpp b/example/tracking/mbtEdgeKltTracking.cpp index 121b704ccf..d12073dc3a 100644 --- a/example/tracking/mbtEdgeKltTracking.cpp +++ b/example/tracking/mbtEdgeKltTracking.cpp @@ -329,8 +329,8 @@ int main(int argc, const char **argv) std::cerr << "Coin is not detected in ViSP. Use the .cao model instead." << std::endl; modelFile = vpIoTools::createFilePath(opt_ipath, modelFileCao); #endif + } } - } else { if (cao3DModel) { modelFile = vpIoTools::createFilePath(env_ipath, modelFileCao); @@ -342,9 +342,9 @@ int main(int argc, const char **argv) std::cerr << "Coin is not detected in ViSP. Use the .cao model instead." << std::endl; modelFile = vpIoTools::createFilePath(env_ipath, modelFileCao); #endif + } } - } -} + } if (!opt_initFile.empty()) initFile = opt_initFile; @@ -563,7 +563,7 @@ int main(int argc, const char **argv) // Test to set an initial pose if (reader.getFrameIndex() == reader.getFirstFrameIndex() + 50) { - cMo.build(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); + cMo.buildFrom(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); vpTRACE("Test set pose"); tracker.setPose(I, cMo); // if (opt_display) { diff --git a/example/tracking/mbtEdgeTracking.cpp b/example/tracking/mbtEdgeTracking.cpp index 424afe0261..9bd5a72db1 100644 --- a/example/tracking/mbtEdgeTracking.cpp +++ b/example/tracking/mbtEdgeTracking.cpp @@ -537,7 +537,7 @@ int main(int argc, const char **argv) // Test to set an initial pose if (reader.getFrameIndex() == reader.getFirstFrameIndex() + 50) { - cMo.build(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); + cMo.buildFrom(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); vpTRACE("Test set pose"); tracker.setPose(I, cMo); // if (opt_display) { diff --git a/example/tracking/mbtGenericTracking.cpp b/example/tracking/mbtGenericTracking.cpp index d02b9f92fa..b83a18cbf8 100644 --- a/example/tracking/mbtGenericTracking.cpp +++ b/example/tracking/mbtGenericTracking.cpp @@ -596,8 +596,8 @@ int main(int argc, const char **argv) // Test to set an initial pose if (reader.getFrameIndex() == reader.getFirstFrameIndex() + 50) { - c1Mo.build(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); - c2Mo.build(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); + c1Mo.buildFrom(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); + c2Mo.buildFrom(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); std::cout << "Test set pose" << std::endl; dynamic_cast(tracker)->setPose(I1, I2, c1Mo, c2Mo); } diff --git a/example/tracking/mbtGenericTracking2.cpp b/example/tracking/mbtGenericTracking2.cpp index f2b7f6f203..3efbb4aaaa 100644 --- a/example/tracking/mbtGenericTracking2.cpp +++ b/example/tracking/mbtGenericTracking2.cpp @@ -665,7 +665,7 @@ int main(int argc, const char **argv) // Test to set an initial pose if (reader.getFrameIndex() == reader.getFirstFrameIndex() + 50) { vpHomogeneousMatrix c1Moi; - c1Moi.build(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); + c1Moi.buildFrom(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); std::map mapOfSetPoses; mapOfSetPoses["Camera1"] = c1Moi; diff --git a/example/tracking/mbtGenericTrackingDepth.cpp b/example/tracking/mbtGenericTrackingDepth.cpp index 129acfeb71..eb920954ae 100644 --- a/example/tracking/mbtGenericTrackingDepth.cpp +++ b/example/tracking/mbtGenericTrackingDepth.cpp @@ -726,12 +726,12 @@ int main(int argc, const char **argv) // Test to set an initial pose #if USE_SMALL_DATASET if (frame_index == 20) { - c1Mo.build(0.07734634051, 0.08993639906, 0.342344402, -2.708409543, 0.0669276477, -0.3798958303); - c2Mo.build(0.05319520317, 0.09223511976, 0.3380095812, -2.71438192, 0.07141055397, -0.3810081638); + c1Mo.buildFrom(0.07734634051, 0.08993639906, 0.342344402, -2.708409543, 0.0669276477, -0.3798958303); + c2Mo.buildFrom(0.05319520317, 0.09223511976, 0.3380095812, -2.71438192, 0.07141055397, -0.3810081638); #else if (frame_index == 50) { - c1Mo.build(0.09280663035, 0.09277655672, 0.330415149, -2.724431817, 0.0293932671, 0.02027966377); - c2Mo.build(0.06865933578, 0.09494713501, 0.3260555142, -2.730027451, 0.03498390135, 0.01989831338); + c1Mo.buildFrom(0.09280663035, 0.09277655672, 0.330415149, -2.724431817, 0.0293932671, 0.02027966377); + c2Mo.buildFrom(0.06865933578, 0.09494713501, 0.3260555142, -2.730027451, 0.03498390135, 0.01989831338); #endif std::cout << "Test set pose" << std::endl; dynamic_cast(tracker)->setPose(I, I_depth, c1Mo, c2Mo); @@ -831,7 +831,7 @@ int main(int argc, const char **argv) tracker = nullptr; return EXIT_SUCCESS; - } + } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; diff --git a/example/tracking/mbtGenericTrackingDepthOnly.cpp b/example/tracking/mbtGenericTrackingDepthOnly.cpp index efe398fda8..a458a52662 100644 --- a/example/tracking/mbtGenericTrackingDepthOnly.cpp +++ b/example/tracking/mbtGenericTrackingDepthOnly.cpp @@ -661,10 +661,10 @@ int main(int argc, const char **argv) // Test set an initial pose #if USE_SMALL_DATASET if (frame_index == 20) { - cMo.build(0.05319520317, 0.09223511976, 0.3380095812, -2.71438192, 0.07141055397, -0.3810081638); + cMo.buildFrom(0.05319520317, 0.09223511976, 0.3380095812, -2.71438192, 0.07141055397, -0.3810081638); #else if (frame_index == 50) { - cMo.build(0.06865933578, 0.09494713501, 0.3260555142, -2.730027451, 0.03498390135, 0.01989831338); + cMo.buildFrom(0.06865933578, 0.09494713501, 0.3260555142, -2.730027451, 0.03498390135, 0.01989831338); #endif std::cout << "Test set pose" << std::endl; dynamic_cast(tracker)->setPose(I_depth, cMo); @@ -777,7 +777,7 @@ int main(int argc, const char **argv) tracker = nullptr; return EXIT_SUCCESS; - } + } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; return EXIT_FAILURE; diff --git a/example/tracking/mbtKltTracking.cpp b/example/tracking/mbtKltTracking.cpp index 4b699827d2..0ef1f76d75 100644 --- a/example/tracking/mbtKltTracking.cpp +++ b/example/tracking/mbtKltTracking.cpp @@ -511,7 +511,7 @@ int main(int argc, const char **argv) // Test to set an initial pose if (reader.getFrameIndex() == reader.getFirstFrameIndex() + 50) { - cMo.build(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); + cMo.buildFrom(0.0439540832, 0.0845870108, 0.5477322481, 2.179498458, 0.8611798108, -0.3491961946); vpTRACE("Test set pose"); tracker.setPose(I, cMo); // if (opt_display) { @@ -579,6 +579,6 @@ int main() "this example." << std::endl; return EXIT_SUCCESS; - } +} #endif diff --git a/modules/core/CMakeLists.txt b/modules/core/CMakeLists.txt index 261772f792..6571aa581a 100644 --- a/modules/core/CMakeLists.txt +++ b/modules/core/CMakeLists.txt @@ -337,7 +337,7 @@ vp_glob_module_copy_data("src/image/private/Rubik-Regular.ttf" "data/font") if(UNIX) vp_set_source_file_compile_flag(src/tools/file/vpIoTools_npy.cpp -Wno-misleading-indentation -Wno-strict-aliasing) - vp_set_source_file_compile_flag(src/image/vpFont.cpp -Wno-float-equal) + vp_set_source_file_compile_flag(src/image/vpFont.cpp -Wno-float-equal -Wno-strict-overflow) else() vp_set_source_file_compile_flag(src/tools/file/vpIoTools_npy.cpp /wd4333) endif() diff --git a/modules/core/include/visp3/core/vpDebug.h b/modules/core/include/visp3/core/vpDebug.h index 4d45ab6c0f..6e84957fb2 100644 --- a/modules/core/include/visp3/core/vpDebug.h +++ b/modules/core/include/visp3/core/vpDebug.h @@ -71,7 +71,7 @@ BEGIN_VISP_NAMESPACE It needs to be initialized with the file name, function name and line, of the place where it is created. It is best used by first - instanciating the object and directly calling the () operator. This + instantiating the object and directly calling the () operator. This is used to mimic variadic macros. This class is used to define the following macros: diff --git a/modules/core/include/visp3/core/vpEigenConversion.h b/modules/core/include/visp3/core/vpEigenConversion.h index 16bce7a59c..08a6f6b564 100644 --- a/modules/core/include/visp3/core/vpEigenConversion.h +++ b/modules/core/include/visp3/core/vpEigenConversion.h @@ -51,13 +51,13 @@ VISP_EXPORT void eigen2visp(const Eigen::MatrixXd &src, vpHomogeneousMatrix &dst template void eigen2visp(const Eigen::Quaternion &src, vpQuaternionVector &dst) { - dst.build(src.x(), src.y(), src.z(), src.w()); + dst.buildFrom(src.x(), src.y(), src.z(), src.w()); } template void eigen2visp(const Eigen::AngleAxis &src, vpThetaUVector &dst) { - dst.build(src.angle() * src.axis()(0), src.angle() * src.axis()(1), src.angle() * src.axis()(2)); + dst.buildFrom(src.angle() * src.axis()(0), src.angle() * src.axis()(1), src.angle() * src.axis()(2)); } VISP_EXPORT void eigen2visp(const Eigen::VectorXd &src, vpColVector &dst); diff --git a/modules/core/include/visp3/core/vpForceTwistMatrix.h b/modules/core/include/visp3/core/vpForceTwistMatrix.h index c28edbc288..eb50c386dc 100644 --- a/modules/core/include/visp3/core/vpForceTwistMatrix.h +++ b/modules/core/include/visp3/core/vpForceTwistMatrix.h @@ -164,7 +164,7 @@ BEGIN_VISP_NAMESPACE vpHomogeneousMatrix sMp; // ... sMp need here to be initialized - sFp.build(sMp); + sFp.buildFrom(sMp); // Force/torque skew in the probe frame: fx,fy,fz,tx,ty,tz vpColVector p_H(6); @@ -197,20 +197,12 @@ class VISP_EXPORT vpForceTwistMatrix : public vpArray2D VP_EXPLICIT vpForceTwistMatrix(const vpRotationMatrix &R); VP_EXPLICIT vpForceTwistMatrix(const vpThetaUVector &thetau); -#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) - VP_DEPRECATED vpForceTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R); - VP_DEPRECATED vpForceTwistMatrix buildFrom(const vpTranslationVector &t, const vpThetaUVector &thetau); - VP_DEPRECATED vpForceTwistMatrix buildFrom(const vpHomogeneousMatrix &M, bool full = true); - - VP_DEPRECATED vpForceTwistMatrix buildFrom(const vpRotationMatrix &R); - VP_DEPRECATED vpForceTwistMatrix buildFrom(const vpThetaUVector &thetau); -#endif - vpForceTwistMatrix &build(const vpTranslationVector &t, const vpRotationMatrix &R); - vpForceTwistMatrix &build(const vpTranslationVector &t, const vpThetaUVector &thetau); - vpForceTwistMatrix &build(const vpHomogeneousMatrix &M, bool full = true); + vpForceTwistMatrix &buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R); + vpForceTwistMatrix &buildFrom(const vpTranslationVector &t, const vpThetaUVector &thetau); + vpForceTwistMatrix &buildFrom(const vpHomogeneousMatrix &M, bool full = true); - vpForceTwistMatrix &build(const vpThetaUVector &thetau); - vpForceTwistMatrix &build(const vpRotationMatrix &R); + vpForceTwistMatrix &buildFrom(const vpRotationMatrix &R); + vpForceTwistMatrix &buildFrom(const vpThetaUVector &thetau); // Basic initialisation (identity) void eye(); diff --git a/modules/core/include/visp3/core/vpHomogeneousMatrix.h b/modules/core/include/visp3/core/vpHomogeneousMatrix.h index 992aff7c10..9d99ccbad3 100644 --- a/modules/core/include/visp3/core/vpHomogeneousMatrix.h +++ b/modules/core/include/visp3/core/vpHomogeneousMatrix.h @@ -233,22 +233,13 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D VP_EXPLICIT vpHomogeneousMatrix(const std::initializer_list &list); #endif -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - VP_DEPRECATED void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R); - VP_DEPRECATED void buildFrom(const vpTranslationVector &t, const vpThetaUVector &tu); - VP_DEPRECATED void buildFrom(const vpTranslationVector &t, const vpQuaternionVector &q); - VP_DEPRECATED void buildFrom(const vpPoseVector &p); - VP_DEPRECATED void buildFrom(const std::vector &v); - VP_DEPRECATED void buildFrom(const std::vector &v); - VP_DEPRECATED void buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz); -#endif - vpHomogeneousMatrix &build(const vpTranslationVector &t, const vpRotationMatrix &R); - vpHomogeneousMatrix &build(const vpTranslationVector &t, const vpThetaUVector &tu); - vpHomogeneousMatrix &build(const vpTranslationVector &t, const vpQuaternionVector &q); - vpHomogeneousMatrix &build(const vpPoseVector &p); - vpHomogeneousMatrix &build(const std::vector &v); - vpHomogeneousMatrix &build(const std::vector &v); - vpHomogeneousMatrix &build(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz); + vpHomogeneousMatrix &buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R); + vpHomogeneousMatrix &buildFrom(const vpTranslationVector &t, const vpThetaUVector &tu); + vpHomogeneousMatrix &buildFrom(const vpTranslationVector &t, const vpQuaternionVector &q); + vpHomogeneousMatrix &buildFrom(const vpPoseVector &p); + vpHomogeneousMatrix &buildFrom(const std::vector &v); + vpHomogeneousMatrix &buildFrom(const std::vector &v); + vpHomogeneousMatrix &buildFrom(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz); void convert(std::vector &M); void convert(std::vector &M); diff --git a/modules/core/include/visp3/core/vpImage_operators.h b/modules/core/include/visp3/core/vpImage_operators.h index be9ae68025..c149815bc0 100644 --- a/modules/core/include/visp3/core/vpImage_operators.h +++ b/modules/core/include/visp3/core/vpImage_operators.h @@ -180,25 +180,39 @@ inline std::ostream &operator<<(std::ostream &s, const vpImage &I) } /*! - \brief Copy operator + \brief Copy operator. + Resizes and copies the contents of the image `other`. + The pointer to the display remains unchanged. + + \param[in] other : Image to copy. + \exception When the display is initialised and the images have different sizes. */ template vpImage &vpImage::operator=(const vpImage &other) { - + if (display != nullptr) { + if ((height != other.height) || (width != other.width)) { + throw(vpException(vpException::dimensionError, + "Error in vpImage::operator=() where the display is initialised but the image size is different")); + } + } resize(other.height, other.width); memcpy(static_cast(bitmap), static_cast(other.bitmap), other.npixels * sizeof(Type)); - if (other.display != nullptr) { - display = other.display; - } return *this; } #if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher - +/*! + * Move operator. + * Moves the image pointers without deep copying image content. + * + * \param[in] other : Image to move. + * \exception + * - When the display is initialised and the images have different sizes. + * - When the display attached to the `other` image is initialized. + */ template vpImage &vpImage::operator=(vpImage &&other) { - if (row != nullptr) { delete[] row; } @@ -207,8 +221,16 @@ template vpImage &vpImage::operator=(vpImage &&ot delete[] bitmap; } bitmap = other.bitmap; + + if (display != nullptr) { + if ((height != other.height) || (width != other.width)) { + throw(vpException(vpException::dimensionError, + "Error in vpImage::operator=(&) where the display is initialised but the image size is different")); + } + } if (other.display != nullptr) { - display = other.display; + throw(vpException(vpException::fatalError, + "Error in vpImage::operator=(&&) where the display of the image to move is initialised")); } height = other.height; width = other.width; diff --git a/modules/core/include/visp3/core/vpIoTools.h b/modules/core/include/visp3/core/vpIoTools.h index b35a341ab6..1ef5371432 100644 --- a/modules/core/include/visp3/core/vpIoTools.h +++ b/modules/core/include/visp3/core/vpIoTools.h @@ -266,7 +266,7 @@ template void npz_save(std::string zipname, std::string fname, const std::vector npy_header = create_npy_header(shape); - size_t nels = std::accumulate(shape.begin(), shape.end(), 1, std::multiplies()); + size_t nels = std::accumulate(shape.begin(), shape.end(), static_cast(1), std::multiplies()); size_t nbytes = nels*sizeof(T) + npy_header.size(); //get the CRC of the data to be added @@ -316,7 +316,9 @@ template void npz_save(std::string zipname, std::string fname, const //write everything fwrite(&local_header[0], sizeof(char), local_header.size(), fp); fwrite(&npy_header[0], sizeof(char), npy_header.size(), fp); - fwrite(&data[0], sizeof(T), nels, fp); + if (data != nullptr) { + fwrite(&data[0], sizeof(T), nels, fp); + } fwrite(&global_header[0], sizeof(char), global_header.size(), fp); fwrite(&footer[0], sizeof(char), footer.size(), fp); fclose(fp); diff --git a/modules/core/include/visp3/core/vpJsonParsing.h b/modules/core/include/visp3/core/vpJsonParsing.h index e70baeab68..65086d5d79 100644 --- a/modules/core/include/visp3/core/vpJsonParsing.h +++ b/modules/core/include/visp3/core/vpJsonParsing.h @@ -100,7 +100,7 @@ bool convertFromTypeAndBuildFrom(const nlohmann::json &j, T &t) if (j["type"] == O::jsonTypeName) { O other; from_json(j, other); - t.build(other); + t.buildFrom(other); return true; } else { diff --git a/modules/core/include/visp3/core/vpNetwork.h b/modules/core/include/visp3/core/vpNetwork.h index faba5b2947..675d4cc18e 100644 --- a/modules/core/include/visp3/core/vpNetwork.h +++ b/modules/core/include/visp3/core/vpNetwork.h @@ -34,6 +34,14 @@ #ifndef VP_NETWORK_H #define VP_NETWORK_H +// Specific case for UWP to introduce a workaround +// error C4996: 'gethostbyname': Use getaddrinfo() or GetAddrInfoW() instead or define _WINSOCK_DEPRECATED_NO_WARNINGS to disable deprecated API warnings +#if defined(WINRT) || defined(_WIN32) +#ifndef _WINSOCK_DEPRECATED_NO_WARNINGS +#define _WINSOCK_DEPRECATED_NO_WARNINGS +#endif +#endif + #include #include #include diff --git a/modules/core/include/visp3/core/vpPolygon.h b/modules/core/include/visp3/core/vpPolygon.h index 7ba9df160b..ea6962aa1d 100644 --- a/modules/core/include/visp3/core/vpPolygon.h +++ b/modules/core/include/visp3/core/vpPolygon.h @@ -117,16 +117,10 @@ class VISP_EXPORT vpPolygon vpPolygon &operator=(const vpPolygon &poly); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - VP_DEPRECATED void buildFrom(const std::vector &corners, const bool create_convex_hull = false); - VP_DEPRECATED void buildFrom(const std::list &corners, const bool create_convex_hull = false); - VP_DEPRECATED void buildFrom(const std::vector &corners, const vpCameraParameters &cam, - const bool create_convex_hull = false); -#endif - vpPolygon &build(const std::vector &corners, const bool &create_convex_hull = false); - vpPolygon &build(const std::list &corners, const bool &create_convex_hull = false); - vpPolygon &build(const std::vector &corners, const vpCameraParameters &cam, - const bool &create_convex_hull = false); + vpPolygon &buildFrom(const std::vector &corners, const bool &create_convex_hull = false); + vpPolygon &buildFrom(const std::list &corners, const bool &create_convex_hull = false); + vpPolygon &buildFrom(const std::vector &corners, const vpCameraParameters &cam, + const bool &create_convex_hull = false); unsigned int getSize() const; void initClick(const vpImage &I, unsigned int size = 5, const vpColor &color = vpColor::red, diff --git a/modules/core/include/visp3/core/vpPoseVector.h b/modules/core/include/visp3/core/vpPoseVector.h index 3823115341..0eb9d1ad2e 100644 --- a/modules/core/include/visp3/core/vpPoseVector.h +++ b/modules/core/include/visp3/core/vpPoseVector.h @@ -215,23 +215,13 @@ class VISP_EXPORT vpPoseVector : public vpArray2D virtual ~vpPoseVector() { } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - VP_DEPRECATED vpPoseVector buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz); + vpPoseVector &buildFrom(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz); // convert an homogeneous matrix in a pose - VP_DEPRECATED vpPoseVector buildFrom(const vpHomogeneousMatrix &M); + vpPoseVector &buildFrom(const vpHomogeneousMatrix &M); // convert a translation and a "thetau" vector into a pose - VP_DEPRECATED vpPoseVector buildFrom(const vpTranslationVector &tv, const vpThetaUVector &tu); + vpPoseVector &buildFrom(const vpTranslationVector &tv, const vpThetaUVector &tu); // convert a translation and a rotation matrix into a pose - VP_DEPRECATED vpPoseVector buildFrom(const vpTranslationVector &tv, const vpRotationMatrix &R); -#endif - - vpPoseVector &build(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz); - // convert an homogeneous matrix in a pose - vpPoseVector &build(const vpHomogeneousMatrix &M); - // convert a translation and a "thetau" vector into a pose - vpPoseVector &build(const vpTranslationVector &tv, const vpThetaUVector &tu); - // convert a translation and a rotation matrix into a pose - vpPoseVector &build(const vpTranslationVector &tv, const vpRotationMatrix &R); + vpPoseVector &buildFrom(const vpTranslationVector &tv, const vpRotationMatrix &R); void extract(vpRotationMatrix &R) const; void extract(vpThetaUVector &tu) const; diff --git a/modules/core/include/visp3/core/vpQuaternionVector.h b/modules/core/include/visp3/core/vpQuaternionVector.h index 21d6eaf93d..5b7488eb26 100644 --- a/modules/core/include/visp3/core/vpQuaternionVector.h +++ b/modules/core/include/visp3/core/vpQuaternionVector.h @@ -113,18 +113,11 @@ class VISP_EXPORT vpQuaternionVector : public vpRotationVector VP_EXPLICIT vpQuaternionVector(const vpColVector &q); VP_EXPLICIT vpQuaternionVector(const std::vector &q); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - VP_DEPRECATED vpQuaternionVector buildFrom(const double qx, const double qy, const double qz, const double qw); - VP_DEPRECATED vpQuaternionVector buildFrom(const vpRotationMatrix &R); - VP_DEPRECATED vpQuaternionVector buildFrom(const vpThetaUVector &tu); - VP_DEPRECATED vpQuaternionVector buildFrom(const vpColVector &q); - VP_DEPRECATED vpQuaternionVector buildFrom(const std::vector &q); -#endif - vpQuaternionVector &build(const double &qx, const double &qy, const double &qz, const double &qw); - vpQuaternionVector &build(const vpRotationMatrix &R); - vpQuaternionVector &build(const vpThetaUVector &tu); - vpQuaternionVector &build(const vpColVector &q); - vpQuaternionVector &build(const std::vector &q); + vpQuaternionVector &buildFrom(const double &qx, const double &qy, const double &qz, const double &qw); + vpQuaternionVector &buildFrom(const vpRotationMatrix &R); + vpQuaternionVector &buildFrom(const vpThetaUVector &tu); + vpQuaternionVector &buildFrom(const vpColVector &q); + vpQuaternionVector &buildFrom(const std::vector &q); void set(double x, double y, double z, double w); diff --git a/modules/core/include/visp3/core/vpRotationMatrix.h b/modules/core/include/visp3/core/vpRotationMatrix.h index 86354aa754..eda483ea94 100644 --- a/modules/core/include/visp3/core/vpRotationMatrix.h +++ b/modules/core/include/visp3/core/vpRotationMatrix.h @@ -145,24 +145,14 @@ class VISP_EXPORT vpRotationMatrix : public vpArray2D VP_EXPLICIT vpRotationMatrix(const std::initializer_list &list); #endif -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - VP_DEPRECATED vpRotationMatrix buildFrom(const vpHomogeneousMatrix &M); - VP_DEPRECATED vpRotationMatrix buildFrom(const vpThetaUVector &v); - VP_DEPRECATED vpRotationMatrix buildFrom(const vpPoseVector &p); - VP_DEPRECATED vpRotationMatrix buildFrom(const vpRzyzVector &v); - VP_DEPRECATED vpRotationMatrix buildFrom(const vpRxyzVector &v); - VP_DEPRECATED vpRotationMatrix buildFrom(const vpRzyxVector &v); - VP_DEPRECATED vpRotationMatrix buildFrom(const vpQuaternionVector &q); - VP_DEPRECATED vpRotationMatrix buildFrom(double tux, double tuy, double tuz); -#endif - vpRotationMatrix &build(const vpHomogeneousMatrix &M); - vpRotationMatrix &build(const vpThetaUVector &v); - vpRotationMatrix &build(const vpPoseVector &p); - vpRotationMatrix &build(const vpRzyzVector &v); - vpRotationMatrix &build(const vpRxyzVector &v); - vpRotationMatrix &build(const vpRzyxVector &v); - vpRotationMatrix &build(const vpQuaternionVector &q); - vpRotationMatrix &build(const double &tux, const double &tuy, const double &tuz); + vpRotationMatrix &buildFrom(const vpHomogeneousMatrix &M); + vpRotationMatrix &buildFrom(const vpThetaUVector &v); + vpRotationMatrix &buildFrom(const vpPoseVector &p); + vpRotationMatrix &buildFrom(const vpRzyzVector &v); + vpRotationMatrix &buildFrom(const vpRxyzVector &v); + vpRotationMatrix &buildFrom(const vpRzyxVector &v); + vpRotationMatrix &buildFrom(const vpQuaternionVector &q); + vpRotationMatrix &buildFrom(const double &tux, const double &tuy, const double &tuz); void eye(); diff --git a/modules/core/include/visp3/core/vpRxyzVector.h b/modules/core/include/visp3/core/vpRxyzVector.h index 79412c568b..aa7de3223f 100644 --- a/modules/core/include/visp3/core/vpRxyzVector.h +++ b/modules/core/include/visp3/core/vpRxyzVector.h @@ -162,7 +162,7 @@ class vpThetaUVector; vpRotationMatrix R(rxyz); // Extract the Euler angles around x,y,z axis from a rotation matrix - rxyz.build(R); + rxyz.buildFrom(R); // Print the extracted Euler angles. Values are the same than the // one used for initialization @@ -194,26 +194,15 @@ class VISP_EXPORT vpRxyzVector : public vpRotationVector VP_EXPLICIT vpRxyzVector(const vpColVector &rxyz); VP_EXPLICIT vpRxyzVector(const std::vector &rxyz); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS // convert a rotation matrix into Rxyz vector - VP_DEPRECATED vpRxyzVector buildFrom(const vpRotationMatrix &R); + vpRxyzVector &buildFrom(const vpRotationMatrix &R); // convert a ThetaU vector into a Rxyz vector - VP_DEPRECATED vpRxyzVector buildFrom(const vpThetaUVector &tu); - VP_DEPRECATED vpRxyzVector buildFrom(const vpColVector &rxyz); - VP_DEPRECATED vpRxyzVector buildFrom(const std::vector &rxyz); + vpRxyzVector &buildFrom(const vpThetaUVector &tu); + vpRxyzVector &buildFrom(const vpColVector &rxyz); + vpRxyzVector &buildFrom(const std::vector &rxyz); - VP_DEPRECATED void buildFrom(double phi, double theta, double psi); -#endif - // convert a rotation matrix into Rxyz vector - vpRxyzVector &build(const vpRotationMatrix &R); - - // convert a ThetaU vector into a Rxyz vector - vpRxyzVector &build(const vpThetaUVector &tu); - vpRxyzVector &build(const vpColVector &rxyz); - vpRxyzVector &build(const std::vector &rxyz); - - vpRxyzVector &build(const double &phi, const double &theta, const double &psi); + vpRxyzVector &buildFrom(const double &phi, const double &theta, const double &psi); vpRxyzVector &operator=(const vpColVector &rxyz); vpRxyzVector &operator=(double x); diff --git a/modules/core/include/visp3/core/vpRzyxVector.h b/modules/core/include/visp3/core/vpRzyxVector.h index f13740e53b..810d66c333 100644 --- a/modules/core/include/visp3/core/vpRzyxVector.h +++ b/modules/core/include/visp3/core/vpRzyxVector.h @@ -164,7 +164,7 @@ class vpThetaUVector; vpRotationMatrix R(rzyx); // Extract the Euler angles around z,y,x axis from a rotation matrix - rzyx.build(R); + rzyx.buildFrom(R); // Print the extracted Euler angles. Values are the same than the // one used for initialization @@ -195,26 +195,15 @@ class VISP_EXPORT vpRzyxVector : public vpRotationVector VP_EXPLICIT vpRzyxVector(const vpColVector &rzyx); VP_EXPLICIT vpRzyxVector(const std::vector &rzyx); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS // convert a rotation matrix into Rzyx vector - VP_DEPRECATED vpRzyxVector buildFrom(const vpRotationMatrix &R); + vpRzyxVector &buildFrom(const vpRotationMatrix &R); // convert a ThetaU vector into a Rzyx vector - VP_DEPRECATED vpRzyxVector buildFrom(const vpThetaUVector &R); - VP_DEPRECATED vpRzyxVector buildFrom(const vpColVector &rxyz); - VP_DEPRECATED vpRzyxVector buildFrom(const std::vector &rxyz); + vpRzyxVector &buildFrom(const vpThetaUVector &R); + vpRzyxVector &buildFrom(const vpColVector &rxyz); + vpRzyxVector &buildFrom(const std::vector &rxyz); - VP_DEPRECATED void buildFrom(double phi, double theta, double psi); -#endif - // convert a rotation matrix into Rzyx vector - vpRzyxVector &build(const vpRotationMatrix &R); - - // convert a ThetaU vector into a Rzyx vector - vpRzyxVector &build(const vpThetaUVector &R); - vpRzyxVector &build(const vpColVector &rxyz); - vpRzyxVector &build(const std::vector &rxyz); - - vpRzyxVector &build(const double &phi, const double &theta, const double &psi); + vpRzyxVector &buildFrom(const double &phi, const double &theta, const double &psi); vpRzyxVector &operator=(const vpColVector &rzyx); vpRzyxVector &operator=(double x); diff --git a/modules/core/include/visp3/core/vpRzyzVector.h b/modules/core/include/visp3/core/vpRzyzVector.h index 75adbc9246..b9177b86f8 100644 --- a/modules/core/include/visp3/core/vpRzyzVector.h +++ b/modules/core/include/visp3/core/vpRzyzVector.h @@ -163,7 +163,7 @@ class vpThetaUVector; vpRotationMatrix R(rzyz); // Extract the Euler angles around z,y,z axis from a rotation matrix - rzyz.build(R); + rzyz.buildFrom(R); // Print the extracted Euler angles. Values are the same than the // one used for initialization @@ -194,26 +194,15 @@ class VISP_EXPORT vpRzyzVector : public vpRotationVector VP_EXPLICIT vpRzyzVector(const vpColVector &rzyz); VP_EXPLICIT vpRzyzVector(const std::vector &rzyz); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS // convert a rotation matrix into Rzyz vector - VP_DEPRECATED vpRzyzVector buildFrom(const vpRotationMatrix &R); + vpRzyzVector &buildFrom(const vpRotationMatrix &R); // convert a ThetaU vector into a Rzyz vector - VP_DEPRECATED vpRzyzVector buildFrom(const vpThetaUVector &R); - VP_DEPRECATED vpRzyzVector buildFrom(const vpColVector &rxyz); - VP_DEPRECATED vpRzyzVector buildFrom(const std::vector &rxyz); + vpRzyzVector &buildFrom(const vpThetaUVector &R); + vpRzyzVector &buildFrom(const vpColVector &rxyz); + vpRzyzVector &buildFrom(const std::vector &rxyz); - VP_DEPRECATED void buildFrom(double phi, double theta, double psi); -#endif - // convert a rotation matrix into Rzyz vector - vpRzyzVector &build(const vpRotationMatrix &R); - - // convert a ThetaU vector into a Rzyz vector - vpRzyzVector &build(const vpThetaUVector &R); - vpRzyzVector &build(const vpColVector &rxyz); - vpRzyzVector &build(const std::vector &rxyz); - - vpRzyzVector &build(const double &phi, const double &theta, const double &psi); + vpRzyzVector &buildFrom(const double &phi, const double &theta, const double &psi); vpRzyzVector &operator=(const vpColVector &rzyz); vpRzyzVector &operator=(double x); diff --git a/modules/core/include/visp3/core/vpThetaUVector.h b/modules/core/include/visp3/core/vpThetaUVector.h index 7f7b57c6d6..438e4026b0 100644 --- a/modules/core/include/visp3/core/vpThetaUVector.h +++ b/modules/core/include/visp3/core/vpThetaUVector.h @@ -153,7 +153,7 @@ class vpQuaternionVector; vpRotationMatrix R(tu); // Extract the theta U angles from a rotation matrix - tu.build(R); + tu.buildFrom(R); // Print the extracted theta U angles. Values are the same than the // one used for initialization @@ -192,42 +192,23 @@ class VISP_EXPORT vpThetaUVector : public vpRotationVector vpThetaUVector(double tux, double tuy, double tuz); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS // convert an homogeneous matrix into Theta U vector - VP_DEPRECATED vpThetaUVector buildFrom(const vpHomogeneousMatrix &M); + vpThetaUVector &buildFrom(const vpHomogeneousMatrix &M); // convert a pose vector into Theta U vector - VP_DEPRECATED vpThetaUVector buildFrom(const vpPoseVector &p); + vpThetaUVector &buildFrom(const vpPoseVector &p); // convert a rotation matrix into Theta U vector - VP_DEPRECATED vpThetaUVector buildFrom(const vpRotationMatrix &R); + vpThetaUVector &buildFrom(const vpRotationMatrix &R); // convert an Rzyx vector into Theta U vector - VP_DEPRECATED vpThetaUVector buildFrom(const vpRzyxVector &rzyx); + vpThetaUVector &buildFrom(const vpRzyxVector &rzyx); // convert an Rzyz vector into Theta U vector - VP_DEPRECATED vpThetaUVector buildFrom(const vpRzyzVector &zyz); + vpThetaUVector &buildFrom(const vpRzyzVector &zyz); // convert an Rxyz vector into Theta U vector - VP_DEPRECATED vpThetaUVector buildFrom(const vpRxyzVector &xyz); - VP_DEPRECATED vpThetaUVector buildFrom(const vpQuaternionVector &q); - VP_DEPRECATED vpThetaUVector buildFrom(const vpColVector &tu); - VP_DEPRECATED vpThetaUVector buildFrom(const std::vector &tu); + vpThetaUVector &buildFrom(const vpRxyzVector &xyz); + vpThetaUVector &buildFrom(const vpQuaternionVector &q); + vpThetaUVector &buildFrom(const vpColVector &tu); + vpThetaUVector &buildFrom(const std::vector &tu); - VP_DEPRECATED void buildFrom(double tux, double tuy, double tuz); -#endif - // convert an homogeneous matrix into Theta U vector - vpThetaUVector &build(const vpHomogeneousMatrix &M); - // convert a pose vector into Theta U vector - vpThetaUVector &build(const vpPoseVector &p); - // convert a rotation matrix into Theta U vector - vpThetaUVector &build(const vpRotationMatrix &R); - // convert an Rzyx vector into Theta U vector - vpThetaUVector &build(const vpRzyxVector &rzyx); - // convert an Rzyz vector into Theta U vector - vpThetaUVector &build(const vpRzyzVector &zyz); - // convert an Rxyz vector into Theta U vector - vpThetaUVector &build(const vpRxyzVector &xyz); - vpThetaUVector &build(const vpQuaternionVector &q); - vpThetaUVector &build(const vpColVector &tu); - vpThetaUVector &build(const std::vector &tu); - - vpThetaUVector &build(const double &tux, const double &tuy, const double &tuz); + vpThetaUVector &buildFrom(const double &tux, const double &tuy, const double &tuz); // extract the angle and the axis from the ThetaU representation void extract(double &theta, vpColVector &u) const; diff --git a/modules/core/include/visp3/core/vpTranslationVector.h b/modules/core/include/visp3/core/vpTranslationVector.h index cdc88a8c6f..7d50768a9f 100644 --- a/modules/core/include/visp3/core/vpTranslationVector.h +++ b/modules/core/include/visp3/core/vpTranslationVector.h @@ -129,16 +129,10 @@ class VISP_EXPORT vpTranslationVector : public vpArray2D VP_EXPLICIT vpTranslationVector(const vpPoseVector &p); VP_EXPLICIT vpTranslationVector(const vpColVector &v); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - VP_DEPRECATED vpTranslationVector buildFrom(double tx, double ty, double tz); - VP_DEPRECATED vpTranslationVector buildFrom(const vpHomogeneousMatrix &M); - VP_DEPRECATED vpTranslationVector buildFrom(const vpPoseVector &p); - VP_DEPRECATED vpTranslationVector buildFrom(const vpColVector &v); -#endif - vpTranslationVector &build(const double &tx, const double &ty, const double &tz); - vpTranslationVector &build(const vpHomogeneousMatrix &M); - vpTranslationVector &build(const vpPoseVector &p); - vpTranslationVector &build(const vpColVector &v); + vpTranslationVector &buildFrom(const double &tx, const double &ty, const double &tz); + vpTranslationVector &buildFrom(const vpHomogeneousMatrix &M); + vpTranslationVector &buildFrom(const vpPoseVector &p); + vpTranslationVector &buildFrom(const vpColVector &v); double frobeniusNorm() const; diff --git a/modules/core/include/visp3/core/vpTriangle.h b/modules/core/include/visp3/core/vpTriangle.h index 58feaffae5..23dd2d4860 100644 --- a/modules/core/include/visp3/core/vpTriangle.h +++ b/modules/core/include/visp3/core/vpTriangle.h @@ -75,10 +75,7 @@ class VISP_EXPORT vpTriangle vpTriangle(const vpImagePoint &iP1, const vpImagePoint &iP2, const vpImagePoint &iP3); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - VP_DEPRECATED void buildFrom(const vpImagePoint &iP1, const vpImagePoint &iP2, const vpImagePoint &iP3); -#endif - vpTriangle &build(const vpImagePoint &iP1, const vpImagePoint &iP2, const vpImagePoint &iP3); + vpTriangle &buildFrom(const vpImagePoint &iP1, const vpImagePoint &iP2, const vpImagePoint &iP3); bool inTriangle(const vpImagePoint &iP, double threshold = 0.00001); diff --git a/modules/core/include/visp3/core/vpVelocityTwistMatrix.h b/modules/core/include/visp3/core/vpVelocityTwistMatrix.h index f37666ca6a..18700db24f 100644 --- a/modules/core/include/visp3/core/vpVelocityTwistMatrix.h +++ b/modules/core/include/visp3/core/vpVelocityTwistMatrix.h @@ -159,7 +159,7 @@ class vpMatrix; vpHomogeneousMatrix fMc; // Fix to camera frame transformation // ... fMc need here to be initialized - fVc.build(fMc); + fVc.buildFrom(fMc); vpColVector c_v(6); // Velocity in the camera frame: vx,vy,vz,wx,wy,wz // ... c_v should here have an initial value @@ -192,18 +192,11 @@ class VISP_EXPORT vpVelocityTwistMatrix : public vpArray2D VP_EXPLICIT vpVelocityTwistMatrix(const vpRotationMatrix &R); VP_EXPLICIT vpVelocityTwistMatrix(const vpThetaUVector &thetau); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - VP_DEPRECATED vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R); - VP_DEPRECATED vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpThetaUVector &thetau); - VP_DEPRECATED vpVelocityTwistMatrix buildFrom(const vpHomogeneousMatrix &M, bool full = true); - VP_DEPRECATED vpVelocityTwistMatrix buildFrom(const vpRotationMatrix &R); - VP_DEPRECATED vpVelocityTwistMatrix buildFrom(const vpThetaUVector &thetau); -#endif - vpVelocityTwistMatrix &build(const vpTranslationVector &t, const vpRotationMatrix &R); - vpVelocityTwistMatrix &build(const vpTranslationVector &t, const vpThetaUVector &thetau); - vpVelocityTwistMatrix &build(const vpHomogeneousMatrix &M, bool full = true); - vpVelocityTwistMatrix &build(const vpRotationMatrix &R); - vpVelocityTwistMatrix &build(const vpThetaUVector &thetau); + vpVelocityTwistMatrix &buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R); + vpVelocityTwistMatrix &buildFrom(const vpTranslationVector &t, const vpThetaUVector &thetau); + vpVelocityTwistMatrix &buildFrom(const vpHomogeneousMatrix &M, bool full = true); + vpVelocityTwistMatrix &buildFrom(const vpRotationMatrix &R); + vpVelocityTwistMatrix &buildFrom(const vpThetaUVector &thetau); void extract(vpRotationMatrix &R) const; void extract(vpTranslationVector &t) const; diff --git a/modules/core/src/math/transformation/vpExponentialMap.cpp b/modules/core/src/math/transformation/vpExponentialMap.cpp index f99c443249..15c6506654 100644 --- a/modules/core/src/math/transformation/vpExponentialMap.cpp +++ b/modules/core/src/math/transformation/vpExponentialMap.cpp @@ -96,7 +96,7 @@ vpHomogeneousMatrix vpExponentialMap::direct(const vpColVector &v, const double u[index_0] = v_dt[index_3]; u[index_1] = v_dt[index_4]; u[index_2] = v_dt[index_5]; - rd.build(u); + rd.buildFrom(u); theta = sqrt((u[index_0] * u[index_0]) + (u[index_1] * u[index_1]) + (u[index_2] * u[index_2])); si = sin(theta); @@ -171,7 +171,7 @@ vpColVector vpExponentialMap::inverse(const vpHomogeneousMatrix &M, const double const unsigned int index_3 = 3; M.extract(Rd); - u.build(Rd); + u.buildFrom(Rd); for (i = 0; i < 3; ++i) { v[3 + i] = u[i]; } diff --git a/modules/core/src/math/transformation/vpForceTwistMatrix.cpp b/modules/core/src/math/transformation/vpForceTwistMatrix.cpp index 573a6cbc25..e3e54d9802 100644 --- a/modules/core/src/math/transformation/vpForceTwistMatrix.cpp +++ b/modules/core/src/math/transformation/vpForceTwistMatrix.cpp @@ -129,10 +129,10 @@ vpForceTwistMatrix::vpForceTwistMatrix(const vpForceTwistMatrix &F) : vpArray2D< vpForceTwistMatrix::vpForceTwistMatrix(const vpHomogeneousMatrix &M, bool full) : vpArray2D(6, 6) { if (full) { - build(M); + buildFrom(M); } else { - build(M.getRotationMatrix()); + buildFrom(M.getRotationMatrix()); } } @@ -158,7 +158,7 @@ vpForceTwistMatrix::vpForceTwistMatrix(const vpHomogeneousMatrix &M, bool full) vpForceTwistMatrix::vpForceTwistMatrix(const vpTranslationVector &t, const vpThetaUVector &thetau) : vpArray2D(6, 6) { - build(t, thetau); + buildFrom(t, thetau); } /*! @@ -178,7 +178,7 @@ vpForceTwistMatrix::vpForceTwistMatrix(const vpTranslationVector &t, const vpThe \param thetau : \f$\theta u\f$ rotation vector used to initialize \f$R\f$. */ -vpForceTwistMatrix::vpForceTwistMatrix(const vpThetaUVector &thetau) : vpArray2D(6, 6) { build(thetau); } +vpForceTwistMatrix::vpForceTwistMatrix(const vpThetaUVector &thetau) : vpArray2D(6, 6) { buildFrom(thetau); } /*! @@ -202,7 +202,7 @@ vpForceTwistMatrix::vpForceTwistMatrix(const vpThetaUVector &thetau) : vpArray2D vpForceTwistMatrix::vpForceTwistMatrix(const vpTranslationVector &t, const vpRotationMatrix &R) : vpArray2D(6, 6) { - build(t, R); + buildFrom(t, R); } /*! @@ -222,7 +222,7 @@ vpForceTwistMatrix::vpForceTwistMatrix(const vpTranslationVector &t, const vpRot \param R : Rotation matrix. */ -vpForceTwistMatrix::vpForceTwistMatrix(const vpRotationMatrix &R) : vpArray2D(6, 6) { build(R); } +vpForceTwistMatrix::vpForceTwistMatrix(const vpRotationMatrix &R) : vpArray2D(6, 6) { buildFrom(R); } /*! @@ -249,7 +249,7 @@ vpForceTwistMatrix::vpForceTwistMatrix(double tx, double ty, double tz, double t { vpTranslationVector T(tx, ty, tz); vpThetaUVector tu(tux, tuy, tuz); - build(T, tu); + buildFrom(T, tu); } /*! @@ -389,9 +389,7 @@ vpColVector vpForceTwistMatrix::operator*(const vpColVector &H) const return Hout; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should rather use build(const vpTranslationVector &t, const vpRotationMatrix &R) Build a force/torque twist transformation matrix from a translation vector \e t and a rotation matrix \e R. @@ -409,145 +407,7 @@ vpColVector vpForceTwistMatrix::operator*(const vpColVector &H) const \param R : Rotation matrix. */ -vpForceTwistMatrix vpForceTwistMatrix::buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R) -{ - build(t, R); - return *this; -} - -/*! - \deprecated You should rather use build(const vpRotationMatrix &R) - Build a block diagonal force/torque twist transformation matrix from a - rotation matrix \e R. - - \f[ - {\bf F} = \left[ - \begin{array}{cc} - {\bf R} & {\bf 0}_{3 \times 3} \\ - {{\bf 0}_{3 \times 3}} & {\bf R} - \end{array} - \right] - \f] - - \param R : Rotation matrix. - -*/ -vpForceTwistMatrix vpForceTwistMatrix::buildFrom(const vpRotationMatrix &R) -{ - build(R); - return *this; -} - -/*! - \deprecated You should rather use build(const vpTranslationVector &tv, const vpThetaUVector &thetau) - Initialize a force/torque twist transformation matrix from a translation - vector \e t and a rotation vector with \f$\theta u \f$ parametrization. - - \f[ - {\bf F} = \left[ - \begin{array}{cc} - {\bf R} & {\bf 0}_{3 \times 3} \\ - {[{\bf t}]}_{\times} \; {\bf R} & {\bf R} - \end{array} - \right] - \f] - - \param tv : Translation vector. - - \param thetau : \f$\theta {\bf u}\f$ rotation vector used to initialise - \f$\bf R \f$. - -*/ -vpForceTwistMatrix vpForceTwistMatrix::buildFrom(const vpTranslationVector &tv, const vpThetaUVector &thetau) -{ - build(tv, vpRotationMatrix(thetau)); - return *this; -} - -/*! - \deprecated You should rather use build(const vpThetaUVector &thetau) - Initialize a force/torque block diagonal twist transformation matrix from a - rotation vector with \f$\theta u \f$ parametrization. - - \f[ - {\bf F} = \left[ - \begin{array}{cc} - {\bf R} & {\bf 0}_{3 \times 3} \\ - {{\bf 0}_{3 \times 3}} & {\bf R} - \end{array} - \right] - \f] - - \param thetau : \f$\theta {\bf u}\f$ rotation vector used to initialise - \f$\bf R \f$. - -*/ -vpForceTwistMatrix vpForceTwistMatrix::buildFrom(const vpThetaUVector &thetau) -{ - build(vpRotationMatrix(thetau)); - return *this; -} - -/*! - \deprecated You should rather use build(const vpHomogeneousMatrix &M, bool full) - Initialize a force/torque twist transformation matrix from an homogeneous - matrix \f$M\f$ with \f[ {\bf M} = \left[\begin{array}{cc} {\bf R} & {\bf t} - \\ {\bf 0}_{1\times 3} & 1 \end{array} \right] \f] - - \param M : Homogeneous matrix \f$M\f$ used to initialize the velocity twist - transformation matrix. - \param full : Boolean used to indicate which matrix should be filled. - - When set to true, use the complete force/torque skew transformation: - \f[ - {\bf F} = \left[ - \begin{array}{cc} - {\bf R} & {\bf 0}_{3 \times 3} \\ - {[{\bf t}]}_{\times} \; {\bf R} & {\bf R} - \end{array} - \right] - \f] - - When set to false, use the block diagonal velocity skew transformation: - \f[ - {\bf F} = \left[ - \begin{array}{cc} - {\bf R} & {\bf 0}_{3 \times 3} \\ - {{\bf 0}_{3 \times 3}} & {\bf R} - \end{array} - \right] - \f] -*/ -vpForceTwistMatrix vpForceTwistMatrix::buildFrom(const vpHomogeneousMatrix &M, bool full) -{ - if (full) { - build(M.getTranslationVector(), M.getRotationMatrix()); - } - else { - build(M.getRotationMatrix()); - } - - return *this; -} -#endif - -/*! - Build a force/torque twist transformation matrix from a translation vector - \e t and a rotation matrix \e R. - - \f[ - {\bf F} = \left[ - \begin{array}{cc} - {\bf R} & {\bf 0}_{3 \times 3} \\ - {[{\bf t}]}_{\times} \; {\bf R} & {\bf R} - \end{array} - \right] - \f] - - \param t : Translation vector. - - \param R : Rotation matrix. - -*/ -vpForceTwistMatrix &vpForceTwistMatrix::build(const vpTranslationVector &t, const vpRotationMatrix &R) +vpForceTwistMatrix &vpForceTwistMatrix::buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R) { vpMatrix skewaR = t.skew(t) * R; @@ -578,7 +438,7 @@ vpForceTwistMatrix &vpForceTwistMatrix::build(const vpTranslationVector &t, cons \param R : Rotation matrix. */ -vpForceTwistMatrix &vpForceTwistMatrix::build(const vpRotationMatrix &R) +vpForceTwistMatrix &vpForceTwistMatrix::buildFrom(const vpRotationMatrix &R) { const unsigned int val_3 = 3; for (unsigned int i = 0; i < val_3; ++i) { @@ -610,9 +470,9 @@ vpForceTwistMatrix &vpForceTwistMatrix::build(const vpRotationMatrix &R) \f$\bf R \f$. */ -vpForceTwistMatrix &vpForceTwistMatrix::build(const vpTranslationVector &tv, const vpThetaUVector &thetau) +vpForceTwistMatrix &vpForceTwistMatrix::buildFrom(const vpTranslationVector &tv, const vpThetaUVector &thetau) { - build(tv, vpRotationMatrix(thetau)); + buildFrom(tv, vpRotationMatrix(thetau)); return *this; } @@ -633,9 +493,9 @@ vpForceTwistMatrix &vpForceTwistMatrix::build(const vpTranslationVector &tv, con \f$\bf R \f$. */ -vpForceTwistMatrix &vpForceTwistMatrix::build(const vpThetaUVector &thetau) +vpForceTwistMatrix &vpForceTwistMatrix::buildFrom(const vpThetaUVector &thetau) { - build(vpRotationMatrix(thetau)); + buildFrom(vpRotationMatrix(thetau)); return *this; } @@ -666,13 +526,13 @@ vpForceTwistMatrix &vpForceTwistMatrix::build(const vpThetaUVector &thetau) \right] \f] */ -vpForceTwistMatrix &vpForceTwistMatrix::build(const vpHomogeneousMatrix &M, bool full) +vpForceTwistMatrix &vpForceTwistMatrix::buildFrom(const vpHomogeneousMatrix &M, bool full) { if (full) { - build(M.getTranslationVector(), M.getRotationMatrix()); + buildFrom(M.getTranslationVector(), M.getRotationMatrix()); } else { - build(M.getRotationMatrix()); + buildFrom(M.getRotationMatrix()); } return *this; diff --git a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp index 20cfcc6edf..0d364cd861 100644 --- a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp @@ -52,7 +52,7 @@ BEGIN_VISP_NAMESPACE vpHomogeneousMatrix::vpHomogeneousMatrix(const vpTranslationVector &t, const vpQuaternionVector &q) : vpArray2D(4, 4) { - build(t, q); + buildFrom(t, q); (*this)[3][3] = 1.; } @@ -77,7 +77,7 @@ vpHomogeneousMatrix::vpHomogeneousMatrix(const vpHomogeneousMatrix &M) : vpArray vpHomogeneousMatrix::vpHomogeneousMatrix(const vpTranslationVector &t, const vpThetaUVector &tu) : vpArray2D(4, 4), m_index(0) { - build(t, tu); + buildFrom(t, tu); (*this)[3][3] = 1.; } @@ -105,7 +105,7 @@ vpHomogeneousMatrix::vpHomogeneousMatrix(const vpPoseVector &p) : vpArray2D &v) : vpArray2D(4, 4), m_index(0) { - build(v); + buildFrom(v); (*this)[3][3] = 1.; } @@ -311,7 +311,7 @@ vpHomogeneousMatrix::vpHomogeneousMatrix(const std::initializer_list &li */ vpHomogeneousMatrix::vpHomogeneousMatrix(const std::vector &v) : vpArray2D(4, 4), m_index(0) { - build(v); + buildFrom(v); (*this)[3][3] = 1.; } @@ -323,168 +323,15 @@ vpHomogeneousMatrix::vpHomogeneousMatrix(const std::vector &v) : vpArray vpHomogeneousMatrix::vpHomogeneousMatrix(double tx, double ty, double tz, double tux, double tuy, double tuz) : vpArray2D(4, 4), m_index(0) { - build(tx, ty, tz, tux, tuy, tuz); + buildFrom(tx, ty, tz, tux, tuy, tuz); (*this)[3][3] = 1.; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use instead build(const vpTranslationVector &, const vpThetaUVector &) Build an homogeneous matrix from a translation vector and a \f$\theta {\bf u}\f$ rotation vector. */ -void vpHomogeneousMatrix::buildFrom(const vpTranslationVector &t, const vpThetaUVector &tu) -{ - build(t, tu); -} - -/*! - \deprecated You should use instead build(const vpTranslationVector &, const vpRotationMatrix &) - Build an homogeneous matrix from a translation vector - and a rotation matrix. - */ -void vpHomogeneousMatrix::buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R) -{ - build(t, R); -} - -/*! - \deprecated You should use instead build(const vpPoseVector &) - Build an homogeneous matrix from a pose vector. - */ -void vpHomogeneousMatrix::buildFrom(const vpPoseVector &p) -{ - build(p); -} - -/*! - \deprecated You should use instead build(const vpTranslationVector &t, const vpQuaternionVector &q) - Build an homogeneous matrix from a translation vector - and a quaternion rotation vector. - */ -void vpHomogeneousMatrix::buildFrom(const vpTranslationVector &t, const vpQuaternionVector &q) -{ - build(t, q); -} - -/*! - \deprecated You should use instead build(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz) - Build an homogeneous matrix from a translation vector \f${\bf t}=(t_x, t_y, - t_z)^T\f$ and a \f$\theta {\bf u}=(\theta u_x, \theta u_y, \theta u_z)^T\f$ - rotation vector. - */ -void vpHomogeneousMatrix::buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz) -{ - build(tx, ty, tz, tux, tuy, tuz); -} - -/*! - \deprecated You should use instead build(const std::vector &) - - Build an homogeneous matrix from a vector of float. - \param v : Vector of 12 or 16 values corresponding to the values of the - homogeneous matrix. - - The following example shows how to use this function: - \code - #include - - #ifdef ENABLE_VISP_NAMESPACE - using namespace VISP_NAMESPACE_NAME; - #endif - - int main() - { - std::vector v(12, 0); - v[1] = -1.; // ry=-90 - v[4] = 1.; // rx=90 - v[10] = -1.; // rz=-90 - v[3] = 0.3; // tx - v[7] = 0.4; // ty - v[11] = 0.5; // tz - - std::cout << "v: "; - for(unsigned int i=0; i &v) -{ - build(v); -} - -/*! - \deprecated You should use instead build(const std::vector &) - Build an homogeneous matrix from a vector of double. - \param v : Vector of 12 or 16 values corresponding to the values of the -homogeneous matrix. - - The following example shows how to use this function: - \code - #include - - #ifdef ENABLE_VISP_NAMESPACE - using namespace VISP_NAMESPACE_NAME; - #endif - - int main() - { - std::vector v(12, 0); - v[1] = -1.; // ry=-90 - v[4] = 1.; // rx=90 - v[10] = -1.; // rz=-90 - v[3] = 0.3; // tx - v[7] = 0.4; // ty - v[11] = 0.5; // tz - - std::cout << "v: "; - for(unsigned int i=0; i &v) -{ - build(v); -} -#endif - -/*! - Build an homogeneous matrix from a translation vector - and a \f$\theta {\bf u}\f$ rotation vector. - */ -vpHomogeneousMatrix &vpHomogeneousMatrix::build(const vpTranslationVector &t, const vpThetaUVector &tu) +vpHomogeneousMatrix &vpHomogeneousMatrix::buildFrom(const vpTranslationVector &t, const vpThetaUVector &tu) { insert(tu); insert(t); @@ -495,7 +342,7 @@ vpHomogeneousMatrix &vpHomogeneousMatrix::build(const vpTranslationVector &t, co Build an homogeneous matrix from a translation vector and a rotation matrix. */ -vpHomogeneousMatrix &vpHomogeneousMatrix::build(const vpTranslationVector &t, const vpRotationMatrix &R) +vpHomogeneousMatrix &vpHomogeneousMatrix::buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R) { insert(R); insert(t); @@ -505,7 +352,7 @@ vpHomogeneousMatrix &vpHomogeneousMatrix::build(const vpTranslationVector &t, co /*! Build an homogeneous matrix from a pose vector. */ -vpHomogeneousMatrix &vpHomogeneousMatrix::build(const vpPoseVector &p) +vpHomogeneousMatrix &vpHomogeneousMatrix::buildFrom(const vpPoseVector &p) { const unsigned int index_0 = 0; const unsigned int index_1 = 1; @@ -525,7 +372,7 @@ vpHomogeneousMatrix &vpHomogeneousMatrix::build(const vpPoseVector &p) Build an homogeneous matrix from a translation vector and a quaternion rotation vector. */ -vpHomogeneousMatrix &vpHomogeneousMatrix::build(const vpTranslationVector &t, const vpQuaternionVector &q) +vpHomogeneousMatrix &vpHomogeneousMatrix::buildFrom(const vpTranslationVector &t, const vpQuaternionVector &q) { insert(t); insert(q); @@ -537,7 +384,7 @@ vpHomogeneousMatrix &vpHomogeneousMatrix::build(const vpTranslationVector &t, co t_z)^T\f$ and a \f$\theta {\bf u}=(\theta u_x, \theta u_y, \theta u_z)^T\f$ rotation vector. */ -vpHomogeneousMatrix &vpHomogeneousMatrix::build(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz) +vpHomogeneousMatrix &vpHomogeneousMatrix::buildFrom(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz) { vpRotationMatrix R(tux, tuy, tuz); vpTranslationVector t(tx, ty, tz); @@ -576,7 +423,7 @@ vpHomogeneousMatrix &vpHomogeneousMatrix::build(const double &tx, const double & std::cout << std::endl; vpHomogeneousMatrix M; - M.build(v); + M.buildFrom(v); std::cout << "M:\n" << M << std::endl; } \endcode @@ -591,7 +438,7 @@ vpHomogeneousMatrix &vpHomogeneousMatrix::build(const double &tx, const double & 0 0 0 1 \endcode */ -vpHomogeneousMatrix &vpHomogeneousMatrix::build(const std::vector &v) +vpHomogeneousMatrix &vpHomogeneousMatrix::buildFrom(const std::vector &v) { if ((v.size() != 12) && (v.size() != 16)) { throw(vpException(vpException::dimensionError, "Cannot convert std::vector to vpHomogeneousMatrix")); @@ -632,7 +479,7 @@ vpHomogeneousMatrix &vpHomogeneousMatrix::build(const std::vector &v) std::cout << std::endl; vpHomogeneousMatrix M; - M.build(v); + M.buildFrom(v); std::cout << "M:\n" << M << std::endl; } \endcode @@ -647,7 +494,7 @@ vpHomogeneousMatrix &vpHomogeneousMatrix::build(const std::vector &v) 0 0 0 1 \endcode */ -vpHomogeneousMatrix &vpHomogeneousMatrix::build(const std::vector &v) +vpHomogeneousMatrix &vpHomogeneousMatrix::buildFrom(const std::vector &v) { if ((v.size() != 12) && (v.size() != 16)) { throw(vpException(vpException::dimensionError, "Cannot convert std::vector to vpHomogeneousMatrix")); @@ -1049,7 +896,7 @@ void vpHomogeneousMatrix::extract(vpThetaUVector &tu) const { vpRotationMatrix R; (*this).extract(R); - tu.build(R); + tu.buildFrom(R); } /*! @@ -1059,7 +906,7 @@ void vpHomogeneousMatrix::extract(vpQuaternionVector &q) const { vpRotationMatrix R; (*this).extract(R); - q.build(R); + q.buildFrom(R); } /*! diff --git a/modules/core/src/math/transformation/vpPoseVector.cpp b/modules/core/src/math/transformation/vpPoseVector.cpp index 1abff87cfd..c64a207e0d 100644 --- a/modules/core/src/math/transformation/vpPoseVector.cpp +++ b/modules/core/src/math/transformation/vpPoseVector.cpp @@ -106,7 +106,7 @@ vpPoseVector::vpPoseVector(double tx, double ty, double tz, double tux, double t */ vpPoseVector::vpPoseVector(const vpTranslationVector &tv, const vpThetaUVector &tu) : vpArray2D(6, 1) { - build(tv, tu); + buildFrom(tv, tu); } /*! @@ -123,7 +123,7 @@ vpPoseVector::vpPoseVector(const vpTranslationVector &tv, const vpThetaUVector & */ vpPoseVector::vpPoseVector(const vpTranslationVector &tv, const vpRotationMatrix &R) : vpArray2D(6, 1) { - build(tv, R); + buildFrom(tv, R); } /*! @@ -136,7 +136,7 @@ vpPoseVector::vpPoseVector(const vpTranslationVector &tv, const vpRotationMatrix initialize the pose vector. */ -vpPoseVector::vpPoseVector(const vpHomogeneousMatrix &M) : vpArray2D(6, 1) { build(M); } +vpPoseVector::vpPoseVector(const vpHomogeneousMatrix &M) : vpArray2D(6, 1) { buildFrom(M); } /*! @@ -170,9 +170,7 @@ void vpPoseVector::set(double tx, double ty, double tz, double tux, double tuy, (*this)[index_5] = tuz; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const double &, const double &, const double &, const double &, const double &, const double &) instead. Build a 6 dimension pose vector \f$ [\bf t, \theta \bf u]^\top\f$ from 3 translations and 3 \f$ \theta \bf{u}\f$ angles. @@ -188,84 +186,7 @@ void vpPoseVector::set(double tx, double ty, double tz, double tux, double tuy, \sa set() */ -vpPoseVector vpPoseVector::buildFrom(double tx, double ty, double tz, double tux, double tuy, double tuz) -{ - build(tx, ty, tz, tux, tuy, tuz); - return *this; -} - -/*! - \deprecated You should use build(const vpHomogeneousMatrix &) instead. - Build a 6 dimension pose vector \f$ [\bf t, \theta \bf u]^\top\f$ from - an homogeneous matrix \f$ \bf M \f$. - - \param M : Homogeneous matrix \f$ \bf M \f$ from which translation \f$ - \bf t \f$ and \f$\theta \bf u \f$ vectors are extracted to initialize - the pose vector. - - \return The build pose vector. - -*/ -vpPoseVector vpPoseVector::buildFrom(const vpHomogeneousMatrix &M) -{ - build(M); - return *this; -} - -/*! - \deprecated You should use build(const vpTranslationVector &, const vpThetaUVector &) instead. - Build a 6 dimension pose vector \f$ [\bf t, \theta \bf u]^\top\f$ - from a translation vector \f$ \bf t \f$ and a \f$\theta \bf u\f$ - vector. - - \param tv : Translation vector \f$ \bf t \f$. - \param tu : \f$\theta \bf u\f$ rotation vector. - - \return The build pose vector. -*/ -vpPoseVector vpPoseVector::buildFrom(const vpTranslationVector &tv, const vpThetaUVector &tu) -{ - build(tv, tu); - return *this; -} - -/*! - \deprecated You should use build(const vpTranslationVector &, const vpRotationMatrix &) instead. - Build a 6 dimension pose vector \f$ [\bf t, \theta \bf u]^\top\f$ - from a translation vector \f$ \bf t \f$ and a rotation matrix \f$ - \bf R \f$. - - \param tv : Translation vector \f$ \bf t \f$. - - \param R : Rotation matrix \f$ \bf R \f$ from which \f$\theta \bf - u\f$ vector is extracted to initialise the pose vector. - - \return The build pose vector. -*/ -vpPoseVector vpPoseVector::buildFrom(const vpTranslationVector &tv, const vpRotationMatrix &R) -{ - build(tv, R); - return *this; -} -#endif - -/*! - Build a 6 dimension pose vector \f$ [\bf t, \theta \bf u]^\top\f$ - from 3 translations and 3 \f$ \theta \bf{u}\f$ angles. - - Translations are expressed in meters, while rotations in radians. - - \param tx,ty,tz : Translations \f$[t_x, t_y, t_z]^\top\f$ - respectively along the x, y and z axis (in meters). - - \param tux,tuy,tuz : Rotations \f$[\theta u_x, \theta u_y, \theta - u_z]^\top\f$ respectively around the x, y and z axis (in radians). - - \return The build pose vector. - - \sa set() -*/ -vpPoseVector &vpPoseVector::build(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz) +vpPoseVector &vpPoseVector::buildFrom(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz) { const unsigned int index_0 = 0; const unsigned int index_1 = 1; @@ -294,13 +215,13 @@ vpPoseVector &vpPoseVector::build(const double &tx, const double &ty, const doub \return The build pose vector. */ -vpPoseVector &vpPoseVector::build(const vpHomogeneousMatrix &M) +vpPoseVector &vpPoseVector::buildFrom(const vpHomogeneousMatrix &M) { vpRotationMatrix R; M.extract(R); vpTranslationVector tv; M.extract(tv); - build(tv, R); + buildFrom(tv, R); return *this; } @@ -315,7 +236,7 @@ vpPoseVector &vpPoseVector::build(const vpHomogeneousMatrix &M) \return The build pose vector. */ -vpPoseVector &vpPoseVector::build(const vpTranslationVector &tv, const vpThetaUVector &tu) +vpPoseVector &vpPoseVector::buildFrom(const vpTranslationVector &tv, const vpThetaUVector &tu) { const unsigned int val_3 = 3; for (unsigned int i = 0; i < val_3; ++i) { @@ -338,12 +259,12 @@ vpPoseVector &vpPoseVector::build(const vpTranslationVector &tv, const vpThetaUV \return The build pose vector. */ -vpPoseVector &vpPoseVector::build(const vpTranslationVector &tv, const vpRotationMatrix &R) +vpPoseVector &vpPoseVector::buildFrom(const vpTranslationVector &tv, const vpRotationMatrix &R) { vpThetaUVector tu; - tu.build(R); + tu.buildFrom(R); - build(tv, tu); + buildFrom(tv, tu); return *this; } @@ -381,12 +302,12 @@ void vpPoseVector::extract(vpThetaUVector &tu) const void vpPoseVector::extract(vpQuaternionVector &q) const { vpRotationMatrix R((*this)[3], (*this)[4], (*this)[5]); - q.build(R); + q.buildFrom(R); } /*! Extract the rotation as a rotation matrix. */ -void vpPoseVector::extract(vpRotationMatrix &R) const { R.build((*this)[3], (*this)[4], (*this)[5]); } +void vpPoseVector::extract(vpRotationMatrix &R) const { R.buildFrom((*this)[3], (*this)[4], (*this)[5]); } /*! Return the translation vector that corresponds to the translation part of the pose vector. diff --git a/modules/core/src/math/transformation/vpQuaternionVector.cpp b/modules/core/src/math/transformation/vpQuaternionVector.cpp index 6e55fa290e..5586a60059 100644 --- a/modules/core/src/math/transformation/vpQuaternionVector.cpp +++ b/modules/core/src/math/transformation/vpQuaternionVector.cpp @@ -60,17 +60,17 @@ vpQuaternionVector::vpQuaternionVector(double x_, double y_, double z_, double w } //! Constructor from a 4-dimension vector of doubles. -vpQuaternionVector::vpQuaternionVector(const vpColVector &q) : vpRotationVector(4) { build(q); } +vpQuaternionVector::vpQuaternionVector(const vpColVector &q) : vpRotationVector(4) { buildFrom(q); } //! Constructor from a 4-dimension vector of doubles. -vpQuaternionVector::vpQuaternionVector(const std::vector &q) : vpRotationVector(4) { build(q); } +vpQuaternionVector::vpQuaternionVector(const std::vector &q) : vpRotationVector(4) { buildFrom(q); } /*! Constructs a quaternion from a rotation matrix. \param R : Matrix containing a rotation. */ -vpQuaternionVector::vpQuaternionVector(const vpRotationMatrix &R) : vpRotationVector(4) { build(R); } +vpQuaternionVector::vpQuaternionVector(const vpRotationMatrix &R) : vpRotationVector(4) { buildFrom(R); } /*! Constructor that initialize \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler @@ -78,7 +78,7 @@ vpQuaternionVector::vpQuaternionVector(const vpRotationMatrix &R) : vpRotationVe \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as input to initialize the Euler angles. */ -vpQuaternionVector::vpQuaternionVector(const vpThetaUVector &tu) : vpRotationVector(4) { build(tu); } +vpQuaternionVector::vpQuaternionVector(const vpThetaUVector &tu) : vpRotationVector(4) { buildFrom(tu); } /*! Manually change values of a quaternion. @@ -99,9 +99,7 @@ void vpQuaternionVector::set(double qx, double qy, double qz, double qw) data[index_3] = qw; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const double &, const double &, const double &, const double &) instead. Manually change values of a quaternion. \param qx : x quaternion parameter. \param qy : y quaternion parameter. @@ -110,68 +108,7 @@ void vpQuaternionVector::set(double qx, double qy, double qz, double qw) \sa set() */ -vpQuaternionVector vpQuaternionVector::buildFrom(const double qx, const double qy, const double qz, const double qw) -{ - build(qx, qy, qz, qw); - return *this; -} - -/*! - \deprecated You should use build(const vpThetaUVector &) instead. - Convert a \f$\theta {\bf u}\f$ vector into a quaternion. - \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as - input. - \return Quaternion vector. -*/ -vpQuaternionVector vpQuaternionVector::buildFrom(const vpThetaUVector &tu) -{ - build(tu); - return *this; -} - -/*! - \deprecated You should use build(const vpColVector &q) instead. - Construct a quaternion vector from a 4-dim vector (x,y,z,w). -*/ -vpQuaternionVector vpQuaternionVector::buildFrom(const vpColVector &q) -{ - build(q); - return *this; -} - -/*! - \deprecated You should use build(const std::vector &q) instead. - Construct a quaternion vector from a 4-dim vector (x,y,z,w). -*/ -vpQuaternionVector vpQuaternionVector::buildFrom(const std::vector &q) -{ - build(q); - return *this; -} - -/*! - \deprecated You should use build(const vpRotationMatrix &) instead. - Constructs a quaternion from a rotation matrix. - - \param R : Rotation matrix. -*/ -vpQuaternionVector vpQuaternionVector::buildFrom(const vpRotationMatrix &R) -{ - build(R); - return *this; -} -#endif - -/*! - Manually change values of a quaternion. - \param qx : x quaternion parameter. - \param qy : y quaternion parameter. - \param qz : z quaternion parameter. - \param qw : w quaternion parameter. - - \sa set() -*/ -vpQuaternionVector &vpQuaternionVector::build(const double &qx, const double &qy, const double &qz, const double &qw) +vpQuaternionVector &vpQuaternionVector::buildFrom(const double &qx, const double &qy, const double &qz, const double &qw) { set(qx, qy, qz, qw); return *this; @@ -183,10 +120,10 @@ vpQuaternionVector &vpQuaternionVector::build(const double &qx, const double &qy input. \return Quaternion vector. */ -vpQuaternionVector &vpQuaternionVector::build(const vpThetaUVector &tu) +vpQuaternionVector &vpQuaternionVector::buildFrom(const vpThetaUVector &tu) { vpRotationMatrix R(tu); - build(R); + buildFrom(R); return *this; } @@ -194,7 +131,7 @@ vpQuaternionVector &vpQuaternionVector::build(const vpThetaUVector &tu) /*! Construct a quaternion vector from a 4-dim vector (x,y,z,w). */ -vpQuaternionVector &vpQuaternionVector::build(const vpColVector &q) +vpQuaternionVector &vpQuaternionVector::buildFrom(const vpColVector &q) { if (q.size() != 4) { throw(vpException(vpException::dimensionError, @@ -211,7 +148,7 @@ vpQuaternionVector &vpQuaternionVector::build(const vpColVector &q) /*! Construct a quaternion vector from a 4-dim vector (x,y,z,w). */ -vpQuaternionVector &vpQuaternionVector::build(const std::vector &q) +vpQuaternionVector &vpQuaternionVector::buildFrom(const std::vector &q) { if (q.size() != 4) { throw(vpException(vpException::dimensionError, @@ -231,7 +168,7 @@ vpQuaternionVector &vpQuaternionVector::build(const std::vector &q) \param R : Rotation matrix. */ -vpQuaternionVector &vpQuaternionVector::build(const vpRotationMatrix &R) +vpQuaternionVector &vpQuaternionVector::buildFrom(const vpRotationMatrix &R) { vpThetaUVector tu(R); vpColVector u; @@ -272,7 +209,10 @@ vpQuaternionVector vpQuaternionVector::operator-(const vpQuaternionVector &q) co } //! Negate operator. Returns a quaternion defined by (-x,-y,-z-,-w). -vpQuaternionVector vpQuaternionVector::operator-() const { return vpQuaternionVector(-x(), -y(), -z(), -w()); } +vpQuaternionVector vpQuaternionVector::operator-() const +{ + return vpQuaternionVector(-x(), -y(), -z(), -w()); +} //! Multiplication by scalar. Returns a quaternion defined by (lx,ly,lz,lw). vpQuaternionVector vpQuaternionVector::operator*(double l) const diff --git a/modules/core/src/math/transformation/vpRotationMatrix.cpp b/modules/core/src/math/transformation/vpRotationMatrix.cpp index 9ad5ca9817..8f23a4df38 100644 --- a/modules/core/src/math/transformation/vpRotationMatrix.cpp +++ b/modules/core/src/math/transformation/vpRotationMatrix.cpp @@ -516,18 +516,18 @@ vpRotationMatrix::vpRotationMatrix(const vpRotationMatrix &M) : vpArray2D(3, 3), m_index(0) { build(M); } +vpRotationMatrix::vpRotationMatrix(const vpHomogeneousMatrix &M) : vpArray2D(3, 3), m_index(0) { buildFrom(M); } /*! Construct a 3-by-3 rotation matrix from \f$ \theta {\bf u}\f$ angle representation. */ -vpRotationMatrix::vpRotationMatrix(const vpThetaUVector &tu) : vpArray2D(3, 3), m_index(0) { build(tu); } +vpRotationMatrix::vpRotationMatrix(const vpThetaUVector &tu) : vpArray2D(3, 3), m_index(0) { buildFrom(tu); } /*! Construct a 3-by-3 rotation matrix from a pose vector. */ -vpRotationMatrix::vpRotationMatrix(const vpPoseVector &p) : vpArray2D(3, 3), m_index(0) { build(p); } +vpRotationMatrix::vpRotationMatrix(const vpPoseVector &p) : vpArray2D(3, 3), m_index(0) { buildFrom(p); } /*! Construct a 3-by-3 rotation matrix from \f$ R(z,y,z) \f$ Euler angle @@ -535,20 +535,20 @@ vpRotationMatrix::vpRotationMatrix(const vpPoseVector &p) : vpArray2D(3, */ vpRotationMatrix::vpRotationMatrix(const vpRzyzVector &euler) : vpArray2D(3, 3), m_index(0) { - build(euler); + buildFrom(euler); } /*! Construct a 3-by-3 rotation matrix from \f$ R(x,y,z) \f$ Euler angle representation. */ -vpRotationMatrix::vpRotationMatrix(const vpRxyzVector &Rxyz) : vpArray2D(3, 3), m_index(0) { build(Rxyz); } +vpRotationMatrix::vpRotationMatrix(const vpRxyzVector &Rxyz) : vpArray2D(3, 3), m_index(0) { buildFrom(Rxyz); } /*! Construct a 3-by-3 rotation matrix from \f$ R(z,y,x) \f$ Euler angle representation. */ -vpRotationMatrix::vpRotationMatrix(const vpRzyxVector &Rzyx) : vpArray2D(3, 3), m_index(0) { build(Rzyx); } +vpRotationMatrix::vpRotationMatrix(const vpRzyxVector &Rzyx) : vpArray2D(3, 3), m_index(0) { buildFrom(Rzyx); } /*! Construct a 3-by-3 rotation matrix from a matrix that contains values corresponding to a rotation matrix. @@ -561,13 +561,13 @@ vpRotationMatrix::vpRotationMatrix(const vpMatrix &R) : vpArray2D(3, 3), */ vpRotationMatrix::vpRotationMatrix(double tux, double tuy, double tuz) : vpArray2D(3, 3), m_index(0) { - build(tux, tuy, tuz); + buildFrom(tux, tuy, tuz); } /*! Construct a 3-by-3 rotation matrix from quaternion angle representation. */ -vpRotationMatrix::vpRotationMatrix(const vpQuaternionVector &q) : vpArray2D(3, 3), m_index(0) { build(q); } +vpRotationMatrix::vpRotationMatrix(const vpQuaternionVector &q) : vpArray2D(3, 3), m_index(0) { buildFrom(q); } #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) /*! @@ -683,9 +683,7 @@ void vpRotationMatrix::printVector() std::cout << std::endl; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const vpThetaUVector &) instead. Transform a \f$ \theta {\bf u}\f$ angle representation into a rotation matrix. @@ -694,106 +692,7 @@ void vpRotationMatrix::printVector() R = \cos{ \theta} \; {I}_{3} + (1 - \cos{ \theta}) \; u u^{T} + \sin{ \theta} \; [u]_\times \f] */ -vpRotationMatrix vpRotationMatrix::buildFrom(const vpThetaUVector &v) -{ - build(v); - return *this; -} - -/*! - \deprecated You should use build(const vpHomogeneousMatrix &) instead. - Build a rotation matrix from an homogeneous matrix. -*/ -vpRotationMatrix vpRotationMatrix::buildFrom(const vpHomogeneousMatrix &M) -{ - build(M); - return *this; -} - -/*! - \deprecated You should use build(const vpPoseVector &) instead. - Build a rotation matrix from a pose vector. - - \sa build(const vpThetaUVector &) -*/ -vpRotationMatrix vpRotationMatrix::buildFrom(const vpPoseVector &p) -{ - return build(p); -} - -/*! - \deprecated You should use build(const vpRzyzVector &) instead. - Transform a vector representing the Euler angle - into a rotation matrix. - Rzyz(\f$ \phi, \theta , \psi \f$) = Rot(\f$ z,\phi \f$) Rot(\f$ y,\theta - \f$) Rot(\f$ z,\psi \f$) - -*/ -vpRotationMatrix vpRotationMatrix::buildFrom(const vpRzyzVector &v) -{ - build(v); - return *this; -} - -/*! - \deprecated You should use build(const vpRxyzVector &) instead. - Transform a vector representing the Rxyz angle into a rotation - matrix. - Rxyz(\f$ \phi,\theta, \psi \f$) = Rot(\f$ x, \psi \f$) Rot(\f$ y, \theta \f$ - ) Rot(\f$ z,\phi \f$) - -*/ -vpRotationMatrix vpRotationMatrix::buildFrom(const vpRxyzVector &v) -{ - build(v); - return *this; -} - -/*! - \deprecated You should use build(const vpRzyxVector &) instead. - Transform a vector representing the Rzyx angle - into a rotation matrix. - Rxyz(\f$ \phi, \theta , \psi \f$) = - Rot(\f$ z, \psi \f$) Rot(\f$ y, \theta \f$)Rot(\f$ x, \phi \f$) -*/ -vpRotationMatrix vpRotationMatrix::buildFrom(const vpRzyxVector &v) -{ - build(v); - return *this; -} - -/*! - \deprecated You should use build(const double &, const double &, const double &) instead. - Construct a 3-by-3 rotation matrix from \f$ \theta {\bf u}=(\theta u_x, - \theta u_y, \theta u_z)^T\f$ angle representation. - */ -vpRotationMatrix vpRotationMatrix::buildFrom(double tux, double tuy, double tuz) -{ - build(tux, tuy, tuz); - return *this; -} - -/*! - \deprecated You should use build(const vpQuaternionVector &) instead. - Construct a 3-by-3 rotation matrix from a quaternion representation. - */ -vpRotationMatrix vpRotationMatrix::buildFrom(const vpQuaternionVector &q) -{ - build(q); - return *this; -} -#endif - -/*! - Transform a \f$ \theta {\bf u}\f$ angle representation into a rotation - matrix. - - The rotation is computed using : - \f[ - R = \cos{ \theta} \; {I}_{3} + (1 - \cos{ \theta}) \; u u^{T} + \sin{ - \theta} \; [u]_\times \f] -*/ -vpRotationMatrix &vpRotationMatrix::build(const vpThetaUVector &v) +vpRotationMatrix &vpRotationMatrix::buildFrom(const vpThetaUVector &v) { double theta, si, co, sinc, mcosc; vpRotationMatrix R; @@ -830,7 +729,7 @@ vpRotationMatrix &vpRotationMatrix::build(const vpThetaUVector &v) /*! Build a rotation matrix from an homogeneous matrix. */ -vpRotationMatrix &vpRotationMatrix::build(const vpHomogeneousMatrix &M) +vpRotationMatrix &vpRotationMatrix::buildFrom(const vpHomogeneousMatrix &M) { const unsigned int val_3 = 3; for (unsigned int i = 0; i < val_3; ++i) { @@ -845,12 +744,12 @@ vpRotationMatrix &vpRotationMatrix::build(const vpHomogeneousMatrix &M) /*! Build a rotation matrix from a pose vector. - \sa build(const vpThetaUVector &) + \sa buildFrom(const vpThetaUVector &) */ -vpRotationMatrix &vpRotationMatrix::build(const vpPoseVector &p) +vpRotationMatrix &vpRotationMatrix::buildFrom(const vpPoseVector &p) { vpThetaUVector tu(p); - return build(tu); + return buildFrom(tu); } /*! @@ -860,7 +759,7 @@ vpRotationMatrix &vpRotationMatrix::build(const vpPoseVector &p) \f$) Rot(\f$ z,\psi \f$) */ -vpRotationMatrix &vpRotationMatrix::build(const vpRzyzVector &v) +vpRotationMatrix &vpRotationMatrix::buildFrom(const vpRzyzVector &v) { double c0, c1, c2, s0, s1, s2; const unsigned int index_0 = 0; @@ -895,7 +794,7 @@ vpRotationMatrix &vpRotationMatrix::build(const vpRzyzVector &v) ) Rot(\f$ z,\phi \f$) */ -vpRotationMatrix &vpRotationMatrix::build(const vpRxyzVector &v) +vpRotationMatrix &vpRotationMatrix::buildFrom(const vpRxyzVector &v) { double c0, c1, c2, s0, s1, s2; const unsigned int index_0 = 0; @@ -928,7 +827,7 @@ vpRotationMatrix &vpRotationMatrix::build(const vpRxyzVector &v) Rxyz(\f$ \phi, \theta , \psi \f$) = Rot(\f$ z, \psi \f$) Rot(\f$ y, \theta \f$)Rot(\f$ x, \phi \f$) */ -vpRotationMatrix &vpRotationMatrix::build(const vpRzyxVector &v) +vpRotationMatrix &vpRotationMatrix::buildFrom(const vpRzyxVector &v) { double c0, c1, c2, s0, s1, s2; const unsigned int index_0 = 0; @@ -961,17 +860,17 @@ vpRotationMatrix &vpRotationMatrix::build(const vpRzyxVector &v) Construct a 3-by-3 rotation matrix from \f$ \theta {\bf u}=(\theta u_x, \theta u_y, \theta u_z)^T\f$ angle representation. */ -vpRotationMatrix &vpRotationMatrix::build(const double &tux, const double &tuy, const double &tuz) +vpRotationMatrix &vpRotationMatrix::buildFrom(const double &tux, const double &tuy, const double &tuz) { vpThetaUVector tu(tux, tuy, tuz); - build(tu); + buildFrom(tu); return *this; } /*! Construct a 3-by-3 rotation matrix from a quaternion representation. */ -vpRotationMatrix &vpRotationMatrix::build(const vpQuaternionVector &q) +vpRotationMatrix &vpRotationMatrix::buildFrom(const vpQuaternionVector &q) { double a = q.w(); double b = q.x(); @@ -1001,7 +900,7 @@ vpRotationMatrix &vpRotationMatrix::build(const vpQuaternionVector &q) vpThetaUVector vpRotationMatrix::getThetaUVector() { vpThetaUVector tu; - tu.build(*this); + tu.buildFrom(*this); return tu; } diff --git a/modules/core/src/math/transformation/vpRxyzVector.cpp b/modules/core/src/math/transformation/vpRxyzVector.cpp index e34fe2e85d..ff10108495 100644 --- a/modules/core/src/math/transformation/vpRxyzVector.cpp +++ b/modules/core/src/math/transformation/vpRxyzVector.cpp @@ -55,14 +55,14 @@ vpRxyzVector::vpRxyzVector(const vpRxyzVector &rxyz) : vpRotationVector(rxyz) { \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. \param psi : \f$\psi\f$ angle around the \f$z\f$ axis. */ -vpRxyzVector::vpRxyzVector(double phi, double theta, double psi) : vpRotationVector(3) { build(phi, theta, psi); } +vpRxyzVector::vpRxyzVector(double phi, double theta, double psi) : vpRotationVector(3) { buildFrom(phi, theta, psi); } /*! Constructor that initialize \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles from a rotation matrix. \param R : Rotation matrix used to initialize the Euler angles. */ -vpRxyzVector::vpRxyzVector(const vpRotationMatrix &R) : vpRotationVector(3) { build(R); } +vpRxyzVector::vpRxyzVector(const vpRotationMatrix &R) : vpRotationVector(3) { buildFrom(R); } /*! Constructor that initialize \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler @@ -70,83 +70,22 @@ vpRxyzVector::vpRxyzVector(const vpRotationMatrix &R) : vpRotationVector(3) { bu \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as input to initialize the Euler angles. */ -vpRxyzVector::vpRxyzVector(const vpThetaUVector &tu) : vpRotationVector(3) { build(tu); } +vpRxyzVector::vpRxyzVector(const vpThetaUVector &tu) : vpRotationVector(3) { buildFrom(tu); } /*! Copy constructor from a 3-dimension vector. */ -vpRxyzVector::vpRxyzVector(const vpColVector &rxyz) : vpRotationVector(3) { build(rxyz); } +vpRxyzVector::vpRxyzVector(const vpColVector &rxyz) : vpRotationVector(3) { buildFrom(rxyz); } /*! Copy constructor from a 3-dimension vector. */ -vpRxyzVector::vpRxyzVector(const std::vector &rxyz) : vpRotationVector(3) { build(rxyz); } +vpRxyzVector::vpRxyzVector(const std::vector &rxyz) : vpRotationVector(3) { buildFrom(rxyz); } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const vpRotationMatrix &) instead. Convert a rotation matrix into a \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. \param R : Rotation matrix used as input. \return \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. */ -vpRxyzVector vpRxyzVector::buildFrom(const vpRotationMatrix &R) -{ - build(R); - return *this; -} - -/*! - \deprecated You should use build(const vpThetaUVector &) instead. - Convert a \f$\theta {\bf u}\f$ vector into a - \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. - \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as input. - \return \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. -*/ -vpRxyzVector vpRxyzVector::buildFrom(const vpThetaUVector &tu) -{ - build(tu); - return *this; -} - -/*! - \deprecated You should use build(const double &, const double &, const double &) instead. - Construction from 3 angles (in radian). - \param phi : \f$\varphi\f$ angle around the \f$x\f$ axis. - \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. - \param psi : \f$\psi\f$ angle around the \f$z\f$ axis. -*/ -void vpRxyzVector::buildFrom(double phi, double theta, double psi) -{ - build(phi, theta, psi); -} - -/*! - \deprecated You should use build(const vpColVector &) instead. - Construct a \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. -*/ -vpRxyzVector vpRxyzVector::buildFrom(const vpColVector &rxyz) -{ - build(rxyz); - return *this; -} - -/*! - \deprecated You should use build(const std::vector &) instead. - Construct a \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. -*/ -vpRxyzVector vpRxyzVector::buildFrom(const std::vector &rxyz) -{ - build(rxyz); - return *this; -} -#endif - -/*! - Convert a rotation matrix into a \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler - angles vector. - - \param R : Rotation matrix used as input. - \return \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. -*/ -vpRxyzVector &vpRxyzVector::build(const vpRotationMatrix &R) +vpRxyzVector &vpRxyzVector::buildFrom(const vpRotationMatrix &R) { double COEF_MIN_ROT = 1e-6; double phi; @@ -166,7 +105,7 @@ vpRxyzVector &vpRxyzVector::build(const vpRotationMatrix &R) double theta = atan2(R[index_0][index_2], (-si * R[index_1][index_2]) + (co * R[index_2][index_2])); double psi = atan2((co * R[index_1][index_0]) + (si * R[index_2][index_0]), (co * R[index_1][index_1]) + (si * R[index_2][index_1])); - build(phi, theta, psi); + buildFrom(phi, theta, psi); return *this; } @@ -177,11 +116,11 @@ vpRxyzVector &vpRxyzVector::build(const vpRotationMatrix &R) \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as input. \return \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. */ -vpRxyzVector &vpRxyzVector::build(const vpThetaUVector &tu) +vpRxyzVector &vpRxyzVector::buildFrom(const vpThetaUVector &tu) { vpRotationMatrix R; - R.build(tu); - build(R); + R.buildFrom(tu); + buildFrom(R); return *this; } @@ -192,7 +131,7 @@ vpRxyzVector &vpRxyzVector::build(const vpThetaUVector &tu) \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. \param psi : \f$\psi\f$ angle around the \f$z\f$ axis. */ -vpRxyzVector &vpRxyzVector::build(const double &phi, const double &theta, const double &psi) +vpRxyzVector &vpRxyzVector::buildFrom(const double &phi, const double &theta, const double &psi) { const unsigned int index_0 = 0; const unsigned int index_1 = 1; @@ -206,7 +145,7 @@ vpRxyzVector &vpRxyzVector::build(const double &phi, const double &theta, const /*! Construct a \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. */ -vpRxyzVector &vpRxyzVector::build(const vpColVector &rxyz) +vpRxyzVector &vpRxyzVector::buildFrom(const vpColVector &rxyz) { if (rxyz.size() != 3) { throw(vpException(vpException::dimensionError, "Cannot construct a R-xyz vector from a %d-dimension col vector", @@ -223,7 +162,7 @@ vpRxyzVector &vpRxyzVector::build(const vpColVector &rxyz) /*! Construct a \f$R_{xyz}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. */ -vpRxyzVector &vpRxyzVector::build(const std::vector &rxyz) +vpRxyzVector &vpRxyzVector::buildFrom(const std::vector &rxyz) { if (rxyz.size() != 3) { throw(vpException(vpException::dimensionError, "Cannot construct a R-xyz vector from a %d-dimension std::vector", diff --git a/modules/core/src/math/transformation/vpRzyxVector.cpp b/modules/core/src/math/transformation/vpRzyxVector.cpp index 22ed429af5..7f5b30ad9f 100644 --- a/modules/core/src/math/transformation/vpRzyxVector.cpp +++ b/modules/core/src/math/transformation/vpRzyxVector.cpp @@ -56,14 +56,14 @@ vpRzyxVector::vpRzyxVector(const vpRzyxVector &rzyx) : vpRotationVector(rzyx) { \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. \param psi : \f$\psi\f$ angle around the \f$x\f$ axis. */ -vpRzyxVector::vpRzyxVector(double phi, double theta, double psi) : vpRotationVector(3) { build(phi, theta, psi); } +vpRzyxVector::vpRzyxVector(double phi, double theta, double psi) : vpRotationVector(3) { buildFrom(phi, theta, psi); } /*! Constructor that initialize \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles from a rotation matrix. \param R : Rotation matrix used to initialize the Euler angles. */ -vpRzyxVector::vpRzyxVector(const vpRotationMatrix &R) : vpRotationVector(3) { build(R); } +vpRzyxVector::vpRzyxVector(const vpRotationMatrix &R) : vpRotationVector(3) { buildFrom(R); } /*! Constructor that initialize \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler @@ -71,17 +71,15 @@ vpRzyxVector::vpRzyxVector(const vpRotationMatrix &R) : vpRotationVector(3) { bu \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as input to initialize the Euler angles. */ -vpRzyxVector::vpRzyxVector(const vpThetaUVector &tu) : vpRotationVector(3) { build(tu); } +vpRzyxVector::vpRzyxVector(const vpThetaUVector &tu) : vpRotationVector(3) { buildFrom(tu); } /*! Copy constructor from a 3-dimension vector. */ -vpRzyxVector::vpRzyxVector(const vpColVector &rzyx) : vpRotationVector(3) { build(rzyx); } +vpRzyxVector::vpRzyxVector(const vpColVector &rzyx) : vpRotationVector(3) { buildFrom(rzyx); } /*! Copy constructor from a 3-dimension vector. */ -vpRzyxVector::vpRzyxVector(const std::vector &rzyx) : vpRotationVector(3) { build(rzyx); } +vpRzyxVector::vpRzyxVector(const std::vector &rzyx) : vpRotationVector(3) { buildFrom(rzyx); } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const vpRotationMatrix &) instead. Convert a rotation matrix into a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector. @@ -91,69 +89,7 @@ vpRzyxVector::vpRzyxVector(const std::vector &rzyx) : vpRotationVector(3 \param R : Rotation matrix used as input. \return \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector. */ -vpRzyxVector vpRzyxVector::buildFrom(const vpRotationMatrix &R) -{ - build(R); - return *this; -} - -/*! - \deprecated You should use build(const vpThetaUVector &) instead. - Convert a \f$\theta {\bf u}\f$ vector into a - \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector. - \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as input. - \return \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector. -*/ -vpRzyxVector vpRzyxVector::buildFrom(const vpThetaUVector &tu) -{ - build(tu); - return *this; -} - -/*! - \deprecated You should use build(const double &, const double &, const double &) instead. - Construction from 3 angles (in radian). - \param phi : \f$\varphi\f$ angle around the \f$z\f$ axis. - \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. - \param psi : \f$\psi\f$ angle around the \f$x\f$ axis. -*/ -void vpRzyxVector::buildFrom(double phi, double theta, double psi) -{ - build(phi, theta, psi); -} - -/*! - \deprecated You should use build(const vpColVector &) instead. - Construct a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vectorfrom a 3-dim vector. -*/ -vpRzyxVector vpRzyxVector::buildFrom(const vpColVector &rzyx) -{ - build(rzyx); - return *this; -} - -/*! - \deprecated You should use build(const std::vector &) instead. - Construct a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. -*/ -vpRzyxVector vpRzyxVector::buildFrom(const std::vector &rzyx) -{ - build(rzyx); - return *this; -} -#endif - -/*! - Convert a rotation matrix into a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler - angles vector. - - Source: R. Paul, Robot Manipulators: Mathematics, Programming, and Control. - MIT Press, 1981, p. 71 - - \param R : Rotation matrix used as input. - \return \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector. -*/ -vpRzyxVector &vpRzyxVector::build(const vpRotationMatrix &R) +vpRzyxVector &vpRzyxVector::buildFrom(const vpRotationMatrix &R) { const unsigned int index_0 = 0; const unsigned int index_1 = 1; @@ -183,7 +119,7 @@ vpRzyxVector &vpRzyxVector::build(const vpRotationMatrix &R) double psi = atan2((si * ax) - (co * ay), (-si * ox) + (co * oy)); - build(phi, theta, psi); + buildFrom(phi, theta, psi); return *this; } @@ -194,11 +130,11 @@ vpRzyxVector &vpRzyxVector::build(const vpRotationMatrix &R) \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as input. \return \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector. */ -vpRzyxVector &vpRzyxVector::build(const vpThetaUVector &tu) +vpRzyxVector &vpRzyxVector::buildFrom(const vpThetaUVector &tu) { vpRotationMatrix R; - R.build(tu); - build(R); + R.buildFrom(tu); + buildFrom(R); return *this; } @@ -209,7 +145,7 @@ vpRzyxVector &vpRzyxVector::build(const vpThetaUVector &tu) \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. \param psi : \f$\psi\f$ angle around the \f$x\f$ axis. */ -vpRzyxVector &vpRzyxVector::build(const double &phi, const double &theta, const double &psi) +vpRzyxVector &vpRzyxVector::buildFrom(const double &phi, const double &theta, const double &psi) { const unsigned int index_0 = 0; const unsigned int index_1 = 1; @@ -221,9 +157,9 @@ vpRzyxVector &vpRzyxVector::build(const double &phi, const double &theta, const } /*! - Construct a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vectorfrom a 3-dim vector. + Construct a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. */ -vpRzyxVector &vpRzyxVector::build(const vpColVector &rzyx) +vpRzyxVector &vpRzyxVector::buildFrom(const vpColVector &rzyx) { if (rzyx.size() != 3) { throw(vpException(vpException::dimensionError, "Cannot construct a R-zyx vector from a %d-dimension col vector", @@ -240,7 +176,7 @@ vpRzyxVector &vpRzyxVector::build(const vpColVector &rzyx) /*! Construct a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. */ -vpRzyxVector &vpRzyxVector::build(const std::vector &rzyx) +vpRzyxVector &vpRzyxVector::buildFrom(const std::vector &rzyx) { if (rzyx.size() != 3) { throw(vpException(vpException::dimensionError, "Cannot construct a R-zyx vector from a %d-dimension std::vector", diff --git a/modules/core/src/math/transformation/vpRzyzVector.cpp b/modules/core/src/math/transformation/vpRzyzVector.cpp index 4a2e19f510..72d6cfba7a 100644 --- a/modules/core/src/math/transformation/vpRzyzVector.cpp +++ b/modules/core/src/math/transformation/vpRzyzVector.cpp @@ -53,14 +53,14 @@ vpRzyzVector::vpRzyzVector(const vpRzyzVector &rzyz) : vpRotationVector(rzyz) { \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. \param psi : \f$\psi\f$ angle around the \f$z\f$ axis. */ -vpRzyzVector::vpRzyzVector(double phi, double theta, double psi) : vpRotationVector(3) { build(phi, theta, psi); } +vpRzyzVector::vpRzyzVector(double phi, double theta, double psi) : vpRotationVector(3) { buildFrom(phi, theta, psi); } /*! Constructor that initialize \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles from a rotation matrix. \param R : Rotation matrix used to initialize the Euler angles. */ -vpRzyzVector::vpRzyzVector(const vpRotationMatrix &R) : vpRotationVector(3) { build(R); } +vpRzyzVector::vpRzyzVector(const vpRotationMatrix &R) : vpRotationVector(3) { buildFrom(R); } /*! Constructor that initialize \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler @@ -68,83 +68,22 @@ vpRzyzVector::vpRzyzVector(const vpRotationMatrix &R) : vpRotationVector(3) { bu \param tu : \f$\theta {\bf u}\f$ representation of a rotation used here as input to initialize the Euler angles. */ -vpRzyzVector::vpRzyzVector(const vpThetaUVector &tu) : vpRotationVector(3) { build(tu); } +vpRzyzVector::vpRzyzVector(const vpThetaUVector &tu) : vpRotationVector(3) { buildFrom(tu); } /*! Copy constructor from a 3-dimension vector. */ -vpRzyzVector::vpRzyzVector(const vpColVector &rzyz) : vpRotationVector(3) { build(rzyz); } +vpRzyzVector::vpRzyzVector(const vpColVector &rzyz) : vpRotationVector(3) { buildFrom(rzyz); } /*! Copy constructor from a 3-dimension vector. */ -vpRzyzVector::vpRzyzVector(const std::vector &rzyz) : vpRotationVector(3) { build(rzyz); } +vpRzyzVector::vpRzyzVector(const std::vector &rzyz) : vpRotationVector(3) { buildFrom(rzyz); } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const vpRotationMatrix &) instead. Convert a rotation matrix into a \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. \param R : Rotation matrix used as input. \return \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. */ -vpRzyzVector vpRzyzVector::buildFrom(const vpRotationMatrix &R) -{ - build(R); - return *this; -} - -/*! - \deprecated You should use build(const vpThetaUVector &) instead. - Convert a \f$\theta {\bf u}\f$ vector into a - \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. \param tu : - \f$\theta {\bf u}\f$ representation of a rotation used here as input. - \return \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. -*/ -vpRzyzVector vpRzyzVector::buildFrom(const vpThetaUVector &tu) -{ - build(tu); - return *this; -} - -/*! - \deprecated You should use build(const vpColVector &) instead. - Construct a \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vectorfrom a 3-dim vector. -*/ -vpRzyzVector vpRzyzVector::buildFrom(const vpColVector &rzyz) -{ - build(rzyz); - return *this; -} - -/*! - \deprecated You should use build(const std::vector &) instead. - Construct a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. -*/ -vpRzyzVector vpRzyzVector::buildFrom(const std::vector &rzyz) -{ - build(rzyz); - return *this; -} - -/*! - \deprecated You should use build(const double &, const double &, const double &) instead. - Construction from 3 angles (in radian). - \param phi : \f$\varphi\f$ angle around the \f$z\f$ axis. - \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. - \param psi : \f$\psi\f$ angle around the \f$z\f$ axis. -*/ -void vpRzyzVector::buildFrom(double phi, double theta, double psi) -{ - build(phi, theta, psi); -} -#endif - -/*! - Convert a rotation matrix into a \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler - angles vector. - - \param R : Rotation matrix used as input. - \return \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. -*/ -vpRzyzVector &vpRzyzVector::build(const vpRotationMatrix &R) +vpRzyzVector &vpRzyzVector::buildFrom(const vpRotationMatrix &R) { double phi; const unsigned int index_0 = 0; @@ -163,7 +102,7 @@ vpRzyzVector &vpRzyzVector::build(const vpRotationMatrix &R) double psi = atan2((-sphi * R[0][0]) + (cphi * R[1][0]), (-sphi * R[0][1]) + (cphi * R[1][1])); - build(phi, theta, psi); + buildFrom(phi, theta, psi); return *this; } @@ -174,19 +113,19 @@ vpRzyzVector &vpRzyzVector::build(const vpRotationMatrix &R) \f$\theta {\bf u}\f$ representation of a rotation used here as input. \return \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vector. */ -vpRzyzVector &vpRzyzVector::build(const vpThetaUVector &tu) +vpRzyzVector &vpRzyzVector::buildFrom(const vpThetaUVector &tu) { vpRotationMatrix R; - R.build(tu); - build(R); + R.buildFrom(tu); + buildFrom(R); return *this; } /*! - Construct a \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vectorfrom a 3-dim vector. + Construct a \f$R_{zyz}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. */ -vpRzyzVector &vpRzyzVector::build(const vpColVector &rzyz) +vpRzyzVector &vpRzyzVector::buildFrom(const vpColVector &rzyz) { if (rzyz.size() != 3) { throw(vpException(vpException::dimensionError, "Cannot construct a R-zyz vector from a %d-dimension col vector", @@ -203,7 +142,7 @@ vpRzyzVector &vpRzyzVector::build(const vpColVector &rzyz) /*! Construct a \f$R_{zyx}=(\varphi,\theta,\psi)\f$ Euler angles vector from a 3-dim vector. */ -vpRzyzVector &vpRzyzVector::build(const std::vector &rzyz) +vpRzyzVector &vpRzyzVector::buildFrom(const std::vector &rzyz) { if (rzyz.size() != 3) { throw(vpException(vpException::dimensionError, "Cannot construct a R-zyx vector from a %d-dimension std::vector", @@ -223,7 +162,7 @@ vpRzyzVector &vpRzyzVector::build(const std::vector &rzyz) \param theta : \f$\theta\f$ angle around the \f$y\f$ axis. \param psi : \f$\psi\f$ angle around the \f$z\f$ axis. */ -vpRzyzVector &vpRzyzVector::build(const double &phi, const double &theta, const double &psi) +vpRzyzVector &vpRzyzVector::buildFrom(const double &phi, const double &theta, const double &psi) { const unsigned int index_0 = 0; const unsigned int index_1 = 1; diff --git a/modules/core/src/math/transformation/vpThetaUVector.cpp b/modules/core/src/math/transformation/vpThetaUVector.cpp index d62c6a291a..2530e2c296 100644 --- a/modules/core/src/math/transformation/vpThetaUVector.cpp +++ b/modules/core/src/math/transformation/vpThetaUVector.cpp @@ -49,36 +49,36 @@ vpThetaUVector::vpThetaUVector() : vpRotationVector(3) { } /*! Copy constructor. */ vpThetaUVector::vpThetaUVector(const vpThetaUVector &tu) : vpRotationVector(tu) { } /*! Copy constructor from a 3-dimension vector. */ -vpThetaUVector::vpThetaUVector(const vpColVector &tu) : vpRotationVector(3) { build(tu); } +vpThetaUVector::vpThetaUVector(const vpColVector &tu) : vpRotationVector(3) { buildFrom(tu); } /*! Initialize a \f$\theta {\bf u}\f$ vector from an homogeneous matrix. */ -vpThetaUVector::vpThetaUVector(const vpHomogeneousMatrix &M) : vpRotationVector(3) { build(M); } +vpThetaUVector::vpThetaUVector(const vpHomogeneousMatrix &M) : vpRotationVector(3) { buildFrom(M); } /*! Initialize a \f$\theta {\bf u}\f$ vector from a pose vector. */ -vpThetaUVector::vpThetaUVector(const vpPoseVector &p) : vpRotationVector(3) { build(p); } +vpThetaUVector::vpThetaUVector(const vpPoseVector &p) : vpRotationVector(3) { buildFrom(p); } /*! Initialize a \f$\theta {\bf u}\f$ vector from a rotation matrix. */ -vpThetaUVector::vpThetaUVector(const vpRotationMatrix &R) : vpRotationVector(3) { build(R); } +vpThetaUVector::vpThetaUVector(const vpRotationMatrix &R) : vpRotationVector(3) { buildFrom(R); } /*! Initialize a \f$\theta {\bf u}\f$ vector from an Euler z-y-x representation vector. */ -vpThetaUVector::vpThetaUVector(const vpRzyxVector &rzyx) : vpRotationVector(3) { build(rzyx); } +vpThetaUVector::vpThetaUVector(const vpRzyxVector &rzyx) : vpRotationVector(3) { buildFrom(rzyx); } /*! Initialize a \f$\theta {\bf u}\f$ vector from an Euler z-y-z representation vector. */ -vpThetaUVector::vpThetaUVector(const vpRzyzVector &rzyz) : vpRotationVector(3) { build(rzyz); } +vpThetaUVector::vpThetaUVector(const vpRzyzVector &rzyz) : vpRotationVector(3) { buildFrom(rzyz); } /*! Initialize a \f$\theta {\bf u}\f$ vector from an Euler x-y-z representation vector. */ -vpThetaUVector::vpThetaUVector(const vpRxyzVector &rxyz) : vpRotationVector(3) { build(rxyz); } +vpThetaUVector::vpThetaUVector(const vpRxyzVector &rxyz) : vpRotationVector(3) { buildFrom(rxyz); } /*! Initialize a \f$\theta {\bf u}\f$ vector from a quaternion representation vector. */ -vpThetaUVector::vpThetaUVector(const vpQuaternionVector &q) : vpRotationVector(3) { build(q); } +vpThetaUVector::vpThetaUVector(const vpQuaternionVector &q) : vpRotationVector(3) { buildFrom(q); } /*! Build a \f$\theta {\bf u}\f$ vector from 3 angles in radians. @@ -100,123 +100,22 @@ vpThetaUVector::vpThetaUVector(const vpQuaternionVector &q) : vpRotationVector(3 tu: 0 1.570796327 3.141592654 \endcode */ -vpThetaUVector::vpThetaUVector(double tux, double tuy, double tuz) : vpRotationVector(3) { build(tux, tuy, tuz); } +vpThetaUVector::vpThetaUVector(double tux, double tuy, double tuz) : vpRotationVector(3) { buildFrom(tux, tuy, tuz); } /*! Build a \f$\theta {\bf u}\f$ vector from a vector of 3 angles in radian. */ -vpThetaUVector::vpThetaUVector(const std::vector &tu) : vpRotationVector(3) { build(tu); } +vpThetaUVector::vpThetaUVector(const std::vector &tu) : vpRotationVector(3) { buildFrom(tu); } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const vpHomogeneousMatrix &) instead. Converts an homogeneous matrix into a \f$\theta {\bf u}\f$ vector. */ -vpThetaUVector vpThetaUVector::buildFrom(const vpHomogeneousMatrix &M) -{ - build(M); - return *this; -} - -/*! - \deprecated You should use build(const vpPoseVector &) instead. - Converts a pose vector into a \f$\theta {\bf u}\f$ vector copying - the \f$\theta {\bf u}\f$ values contained in the pose vector. -*/ -vpThetaUVector vpThetaUVector::buildFrom(const vpPoseVector &p) -{ - build(p); - return *this; -} - -/*! - \deprecated You should use build(const vpRotationMatrix &) instead. - Converts a rotation matrix into a \f$\theta {\bf u}\f$ vector. -*/ -vpThetaUVector vpThetaUVector::buildFrom(const vpRotationMatrix &R) -{ - build(R); - return *this; -} - -/*! - \deprecated You should use build(const vpRzyxVector &) instead. - Build a \f$\theta {\bf u}\f$ vector from an Euler z-y-x representation vector. -*/ -vpThetaUVector vpThetaUVector::buildFrom(const vpRzyxVector &rzyx) -{ - build(rzyx); - return *this; -} -/*! - \deprecated You should use build(const vpRzyzVector &) instead. - Build a \f$\theta {\bf u}\f$ vector from an Euler z-y-z representation vector. -*/ -vpThetaUVector vpThetaUVector::buildFrom(const vpRzyzVector &rzyz) -{ - build(rzyz); - return *this; -} - -/*! - \deprecated You should use build(const vpRxyzVector &) instead. - Build a \f$\theta {\bf u}\f$ vector from an Euler x-y-z representation vector. -*/ -vpThetaUVector vpThetaUVector::buildFrom(const vpRxyzVector &rxyz) -{ - build(rxyz); - return *this; -} - -/*! - \deprecated You should use build(const vpQuaternionVector &) instead. - Build a \f$\theta {\bf u}\f$ vector from a quaternion representation vector. -*/ -vpThetaUVector vpThetaUVector::buildFrom(const vpQuaternionVector &q) -{ - build(q); - return *this; -} - -/*! - \deprecated You should use build(const std::vector &) instead. - Build a \f$\theta {\bf u}\f$ vector from a 3-dim vectors. -*/ -vpThetaUVector vpThetaUVector::buildFrom(const std::vector &tu) -{ - build(tu); - return *this; -} - -/*! - \deprecated You should use build(const vpColVector &) instead. - Build a \f$\theta {\bf u}\f$ vector from a 3-dim vector. -*/ -vpThetaUVector vpThetaUVector::buildFrom(const vpColVector &tu) -{ - build(tu); - return *this; -} - -/*! - \deprecated You should use build(const double &, const double &, const double &) instead. - Build a \f$\theta {\bf u}\f$ vector from 3 angles in radian. -*/ -void vpThetaUVector::buildFrom(double tux, double tuy, double tuz) -{ - build(tux, tuy, tuz); -} -#endif - -/*! - Converts an homogeneous matrix into a \f$\theta {\bf u}\f$ vector. -*/ -vpThetaUVector &vpThetaUVector::build(const vpHomogeneousMatrix &M) +vpThetaUVector &vpThetaUVector::buildFrom(const vpHomogeneousMatrix &M) { vpRotationMatrix R; M.extract(R); - build(R); + buildFrom(R); return *this; } @@ -224,7 +123,7 @@ vpThetaUVector &vpThetaUVector::build(const vpHomogeneousMatrix &M) Converts a pose vector into a \f$\theta {\bf u}\f$ vector copying the \f$\theta {\bf u}\f$ values contained in the pose vector. */ -vpThetaUVector &vpThetaUVector::build(const vpPoseVector &p) +vpThetaUVector &vpThetaUVector::buildFrom(const vpPoseVector &p) { const unsigned int val_3 = 3; for (unsigned int i = 0; i < val_3; ++i) { @@ -237,7 +136,7 @@ vpThetaUVector &vpThetaUVector::build(const vpPoseVector &p) /*! Converts a rotation matrix into a \f$\theta {\bf u}\f$ vector. */ -vpThetaUVector &vpThetaUVector::build(const vpRotationMatrix &R) +vpThetaUVector &vpThetaUVector::buildFrom(const vpRotationMatrix &R) { double s, c, theta; const unsigned int index_0 = 0; @@ -319,49 +218,49 @@ vpThetaUVector &vpThetaUVector::build(const vpRotationMatrix &R) /*! Build a \f$\theta {\bf u}\f$ vector from an Euler z-y-x representation vector. */ -vpThetaUVector &vpThetaUVector::build(const vpRzyxVector &rzyx) +vpThetaUVector &vpThetaUVector::buildFrom(const vpRzyxVector &rzyx) { vpRotationMatrix R(rzyx); - build(R); + buildFrom(R); return *this; } /*! Build a \f$\theta {\bf u}\f$ vector from an Euler z-y-z representation vector. */ -vpThetaUVector &vpThetaUVector::build(const vpRzyzVector &rzyz) +vpThetaUVector &vpThetaUVector::buildFrom(const vpRzyzVector &rzyz) { vpRotationMatrix R(rzyz); - build(R); + buildFrom(R); return *this; } /*! Build a \f$\theta {\bf u}\f$ vector from an Euler x-y-z representation vector. */ -vpThetaUVector &vpThetaUVector::build(const vpRxyzVector &rxyz) +vpThetaUVector &vpThetaUVector::buildFrom(const vpRxyzVector &rxyz) { vpRotationMatrix R(rxyz); - build(R); + buildFrom(R); return *this; } /*! Build a \f$\theta {\bf u}\f$ vector from a quaternion representation vector. */ -vpThetaUVector &vpThetaUVector::build(const vpQuaternionVector &q) +vpThetaUVector &vpThetaUVector::buildFrom(const vpQuaternionVector &q) { vpRotationMatrix R(q); - build(R); + buildFrom(R); return *this; } /*! Build a \f$\theta {\bf u}\f$ vector from a 3-dim vectors. */ -vpThetaUVector &vpThetaUVector::build(const std::vector &tu) +vpThetaUVector &vpThetaUVector::buildFrom(const std::vector &tu) { if (tu.size() != 3) { throw(vpException(vpException::dimensionError, "Cannot construct a theta-u vector from a %d-dimension std::vector", @@ -378,7 +277,7 @@ vpThetaUVector &vpThetaUVector::build(const std::vector &tu) /*! Build a \f$\theta {\bf u}\f$ vector from a 3-dim vector. */ -vpThetaUVector &vpThetaUVector::build(const vpColVector &tu) +vpThetaUVector &vpThetaUVector::buildFrom(const vpColVector &tu) { if (tu.size() != 3) { throw(vpException(vpException::dimensionError, "Cannot construct a theta-u vector from a %d-dimension std::vector", @@ -395,7 +294,7 @@ vpThetaUVector &vpThetaUVector::build(const vpColVector &tu) /*! Build a \f$\theta {\bf u}\f$ vector from 3 angles in radian. */ -vpThetaUVector &vpThetaUVector::build(const double &tux, const double &tuy, const double &tuz) +vpThetaUVector &vpThetaUVector::buildFrom(const double &tux, const double &tuy, const double &tuz) { const unsigned int index_0 = 0; const unsigned int index_1 = 1; diff --git a/modules/core/src/math/transformation/vpTranslationVector.cpp b/modules/core/src/math/transformation/vpTranslationVector.cpp index c152f84cc8..ab41fde0d5 100644 --- a/modules/core/src/math/transformation/vpTranslationVector.cpp +++ b/modules/core/src/math/transformation/vpTranslationVector.cpp @@ -124,9 +124,7 @@ vpTranslationVector::vpTranslationVector(const vpColVector &v) : vpArray2D(6, 6) { if (full) { - build(M); + buildFrom(M); } else { - build(M.getRotationMatrix()); + buildFrom(M.getRotationMatrix()); } } @@ -139,7 +139,7 @@ vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpHomogeneousMatrix &M, bool vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpTranslationVector &t, const vpThetaUVector &thetau) : vpArray2D(6, 6) { - build(t, thetau); + buildFrom(t, thetau); } /*! @@ -156,7 +156,7 @@ vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpTranslationVector &t, const */ vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpThetaUVector &thetau) : vpArray2D(6, 6) { - build(thetau); + buildFrom(thetau); } /*! @@ -175,7 +175,7 @@ vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpThetaUVector &thetau) : vpA vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpTranslationVector &t, const vpRotationMatrix &R) : vpArray2D(6, 6) { - build(t, R); + buildFrom(t, R); } /*! @@ -189,7 +189,7 @@ vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpTranslationVector &t, const \param R : Rotation matrix. */ -vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpRotationMatrix &R) : vpArray2D(6, 6) { build(R); } +vpVelocityTwistMatrix::vpVelocityTwistMatrix(const vpRotationMatrix &R) : vpArray2D(6, 6) { buildFrom(R); } /*! @@ -211,7 +211,7 @@ vpVelocityTwistMatrix::vpVelocityTwistMatrix(double tx, double ty, double tz, do { vpTranslationVector t(tx, ty, tz); vpThetaUVector tu(tux, tuy, tuz); - build(t, tu); + buildFrom(t, tu); } /*! @@ -335,108 +335,6 @@ vpColVector vpVelocityTwistMatrix::operator*(const vpColVector &v) const return c; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -/*! - \deprecated You should use build(const vpRotationMatrix &) instead. - Build a velocity twist transformation block diagonal matrix from a rotation - matrix R. - - \f[ {\bf V} = \left[\begin{array}{cc} {\bf R} & {\bf 0}_{3\times 3} \\ - {\bf 0}_{3\times 3} & {\bf R} \end{array} \right] \f] - - \param R : Rotation matrix. - -*/ -vpVelocityTwistMatrix vpVelocityTwistMatrix::buildFrom(const vpRotationMatrix &R) -{ - build(R); - return *this; -} - -/*! - \deprecated You should use build(const vpTranslationVector &, const vpRotationMatrix &) instead. - Build a velocity twist transformation matrix from a translation vector - \e t and a rotation matrix \e R. - - \f[ {\bf V} = \left[\begin{array}{cc} {\bf R} & [{\bf t}]_\times \; {\bf R} - \\ - {\bf 0}_{3\times 3} & {\bf R} \end{array} \right] \f] - - \param t : Translation vector. - - \param R : Rotation matrix. - -*/ -vpVelocityTwistMatrix vpVelocityTwistMatrix::buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R) -{ - build(t, R); - return *this; -} - -/*! - \deprecated You should use build(const vpTranslationVector &, const vpThetaUVector &) instead. - Initialize a velocity twist transformation matrix from a translation vector - \e t and a rotation vector with \f$\theta u \f$ parametrization. - - \f[ {\bf V} = \left[\begin{array}{cc} {\bf R} & [{\bf t}]_\times \; {\bf R} - \\ - {\bf 0}_{3\times 3} & {\bf R} \end{array} \right] \f] - - \param t : Translation vector. - - \param thetau : \f$\theta {\bf u}\f$ rotation vector used to create rotation - matrix \f${\bf R}\f$. - -*/ -vpVelocityTwistMatrix vpVelocityTwistMatrix::buildFrom(const vpTranslationVector &t, const vpThetaUVector &thetau) -{ - build(t, thetau); - return *this; -} - -/*! - \deprecated You should use build(const vpThetaUVector &) instead. - Initialize a velocity twist transformation matrix from a rotation vector - with \f$\theta u \f$ parametrization. - - \f[ {\bf V} = \left[\begin{array}{cc} {\bf R} & {\bf 0}_{3\times 3} \\ - {\bf 0}_{3\times 3} & {\bf R} \end{array} \right] \f] - - \param thetau : \f$\theta {\bf u}\f$ rotation vector used to create rotation - matrix \f${\bf R}\f$. - -*/ -vpVelocityTwistMatrix vpVelocityTwistMatrix::buildFrom(const vpThetaUVector &thetau) -{ - build(thetau); - return *this; -} - -/*! - \deprecated You should use build(const vpHomogeneousMatrix &, bool) instead. - Initialize a velocity twist transformation matrix from an homogeneous matrix - \f$M\f$ with \f[ {\bf M} = \left[\begin{array}{cc} {\bf R} & {\bf t} - \\ {\bf 0}_{1\times 3} & 1 \end{array} \right] \f] - - \param M : Homogeneous matrix \f$M\f$ used to initialize the velocity twist - transformation matrix. - \param full : Boolean used to indicate which matrix should be filled. - - When set to true, use the complete velocity skew transformation : - \f[ {\bf V} = \left[\begin{array}{cc} {\bf R} & [{\bf t}]_\times \; {\bf R} - \\ - {\bf 0}_{3\times 3} & {\bf R} \end{array} \right] \f] - - When set to false, use the block diagonal velocity skew transformation: - \f[ {\bf V} = \left[\begin{array}{cc} {\bf R} & {\bf 0}_{3\times 3} \\ - {\bf 0}_{3\times 3} & {\bf R} \end{array} \right] \f] - -*/ -vpVelocityTwistMatrix vpVelocityTwistMatrix::buildFrom(const vpHomogeneousMatrix &M, bool full) -{ - build(M, full); - return *this; -} -#endif - /*! Build a velocity twist transformation block diagonal matrix from a rotation @@ -448,7 +346,7 @@ vpVelocityTwistMatrix vpVelocityTwistMatrix::buildFrom(const vpHomogeneousMatrix \param R : Rotation matrix. */ -vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpRotationMatrix &R) +vpVelocityTwistMatrix &vpVelocityTwistMatrix::buildFrom(const vpRotationMatrix &R) { const unsigned int val_3 = 3; for (unsigned int i = 0; i < val_3; ++i) { @@ -475,7 +373,7 @@ vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpRotationMatrix &R) \param R : Rotation matrix. */ -vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpTranslationVector &t, const vpRotationMatrix &R) +vpVelocityTwistMatrix &vpVelocityTwistMatrix::buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R) { vpMatrix skewaR = t.skew(t) * R; @@ -506,9 +404,9 @@ vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpTranslationVector &t matrix \f${\bf R}\f$. */ -vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpTranslationVector &t, const vpThetaUVector &thetau) +vpVelocityTwistMatrix &vpVelocityTwistMatrix::buildFrom(const vpTranslationVector &t, const vpThetaUVector &thetau) { - build(t, vpRotationMatrix(thetau)); + buildFrom(t, vpRotationMatrix(thetau)); return *this; } @@ -524,9 +422,9 @@ vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpTranslationVector &t matrix \f${\bf R}\f$. */ -vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpThetaUVector &thetau) +vpVelocityTwistMatrix &vpVelocityTwistMatrix::buildFrom(const vpThetaUVector &thetau) { - build(vpRotationMatrix(thetau)); + buildFrom(vpRotationMatrix(thetau)); return *this; } @@ -548,13 +446,13 @@ vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpThetaUVector &thetau {\bf 0}_{3\times 3} & {\bf R} \end{array} \right] \f] */ -vpVelocityTwistMatrix &vpVelocityTwistMatrix::build(const vpHomogeneousMatrix &M, bool full) +vpVelocityTwistMatrix &vpVelocityTwistMatrix::buildFrom(const vpHomogeneousMatrix &M, bool full) { if (full) { - build(M.getTranslationVector(), M.getRotationMatrix()); + buildFrom(M.getTranslationVector(), M.getRotationMatrix()); } else { - build(M.getRotationMatrix()); + buildFrom(M.getRotationMatrix()); } return *this; @@ -571,7 +469,7 @@ vpVelocityTwistMatrix vpVelocityTwistMatrix::inverse() const vpTranslationVector RtT; RtT = -(R.t() * T); - Wi.build(RtT, R.t()); + Wi.buildFrom(RtT, R.t()); return Wi; } diff --git a/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp index 49798c4440..dc6b3874d9 100644 --- a/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp @@ -294,7 +294,7 @@ class vpXmlParserHomogeneousMatrix::Impl } // Create the Homogeneous matrix - M.build(tx_, ty_, tz_, tux_, tuy_, tuz_); + M.buildFrom(tx_, ty_, tz_, tux_, tuy_, tuz_); // --comment: std::cout << "Read values from file:" << std::endl; // --comment: std::cout << "tx:" << tx_<< std::endl; diff --git a/modules/core/src/munkres/vpMunkres.cpp b/modules/core/src/munkres/vpMunkres.cpp index 05b20113e1..927bcee9c9 100644 --- a/modules/core/src/munkres/vpMunkres.cpp +++ b/modules/core/src/munkres/vpMunkres.cpp @@ -1,7 +1,6 @@ -/**************************************************************************** - * +/* * ViSP, open source Visual Servoing Platform software. - * Copyright (C) 2005 - 2023 by Inria. All rights reserved. + * Copyright (C) 2005 - 2024 by Inria. All rights reserved. * * This software is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -30,12 +29,7 @@ * * Description: * Class for Munkres Assignment Algorithm. - * - * Authors: - * Souriya Trinh - * Julien Dufour - * -*****************************************************************************/ + */ #include @@ -50,8 +44,8 @@ BEGIN_VISP_NAMESPACE * \param[in] row: Row index. * \return Index of the starred zero [col] or std::nullopt if the mask matrix row does not contain a starred zero. */ -std::optional vpMunkres::findStarInRow(const std::vector > &mask, - const unsigned int &row) + std::optional vpMunkres::findStarInRow(const std::vector > &mask, + const unsigned int &row) { const auto it = std::find(begin(mask.at(row)), end(mask.at(row)), vpMunkres::ZERO_T::STARRED); return it != end(mask.at(row)) ? std::make_optional(std::distance(begin(mask.at(row)), it)) diff --git a/modules/core/src/tools/geometry/vpPolygon.cpp b/modules/core/src/tools/geometry/vpPolygon.cpp index 5e10d986ac..9aec00c9a5 100644 --- a/modules/core/src/tools/geometry/vpPolygon.cpp +++ b/modules/core/src/tools/geometry/vpPolygon.cpp @@ -181,9 +181,7 @@ vpPolygon &vpPolygon::operator=(const vpPolygon &poly) return *this; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const std::vector &, const bool &) instead. Initialises the triangle thanks to the collection of 2D points (in pixel). \warning the corners must be ordered (either clockwise or counter @@ -192,56 +190,7 @@ vpPolygon &vpPolygon::operator=(const vpPolygon &poly) \param corners : The corners of the polygon. \param create_convex_hull: Create a convex hull from the given corners. */ -void vpPolygon::buildFrom(const std::vector &corners, const bool create_convex_hull) -{ - build(corners, create_convex_hull); -} - -/*! - \deprecated You should use build(const std::list &, const bool &) instead. - Initialises the polygon thanks to the collection of 2D points (in pixel). - - \warning the corners must be ordered (either clockwise or counter - clockwise). - - \param corners : The corners of the polygon. - \param create_convex_hull: Create a convex hull from the given corners. -*/ -void vpPolygon::buildFrom(const std::list &corners, const bool create_convex_hull) -{ - build(corners, create_convex_hull); -} - -/*! - \deprecated You should use build(const std::vector &, const vpCameraParameters &, const bool &) instead. - Initialises the triangle thanks to the collection of 2D points (in meter). - The fields \e x and \e y are used to compute the corresponding coordinates - in pixel thanks to the camera parameters \e cam. - - \warning the corners must be ordered (either clockwise or counter - clockwise). - - \param corners : The corners of the polygon. - \param cam : The camera parameters used to convert the coordinates from meter to pixel. - \param create_convex_hull: Create a convex hull from the given corners. -*/ -void vpPolygon::buildFrom(const std::vector &corners, const vpCameraParameters &cam, - const bool create_convex_hull) -{ - build(corners, cam, create_convex_hull); -} -#endif - -/*! - Initialises the triangle thanks to the collection of 2D points (in pixel). - - \warning the corners must be ordered (either clockwise or counter - clockwise). - - \param corners : The corners of the polygon. - \param create_convex_hull: Create a convex hull from the given corners. -*/ -vpPolygon &vpPolygon::build(const std::vector &corners, const bool &create_convex_hull) +vpPolygon &vpPolygon::buildFrom(const std::vector &corners, const bool &create_convex_hull) { if (create_convex_hull) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) @@ -265,7 +214,7 @@ vpPolygon &vpPolygon::build(const std::vector &corners, const bool \param corners : The corners of the polygon. \param create_convex_hull: Create a convex hull from the given corners. */ -vpPolygon &vpPolygon::build(const std::list &corners, const bool &create_convex_hull) +vpPolygon &vpPolygon::buildFrom(const std::list &corners, const bool &create_convex_hull) { if (create_convex_hull) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) @@ -292,15 +241,15 @@ vpPolygon &vpPolygon::build(const std::list &corners, const bool & \param cam : The camera parameters used to convert the coordinates from meter to pixel. \param create_convex_hull: Create a convex hull from the given corners. */ -vpPolygon &vpPolygon::build(const std::vector &corners, const vpCameraParameters &cam, - const bool &create_convex_hull) +vpPolygon &vpPolygon::buildFrom(const std::vector &corners, const vpCameraParameters &cam, + const bool &create_convex_hull) { std::vector ipCorners(corners.size()); size_t corners_size = corners.size(); for (size_t i = 0; i < corners_size; ++i) { vpMeterPixelConversion::convertPoint(cam, corners[i].get_x(), corners[i].get_y(), ipCorners[i]); } - build(ipCorners, create_convex_hull); + buildFrom(ipCorners, create_convex_hull); return *this; } @@ -330,7 +279,7 @@ void vpPolygon::initClick(const vpImage &I, unsigned int size, co } } - build(cornersClick); + buildFrom(cornersClick); } /*! @@ -358,7 +307,7 @@ void vpPolygon::initClick(const vpImage &I, unsigned int size, const vpC } } - build(cornersClick); + buildFrom(cornersClick); } /*! diff --git a/modules/core/src/tools/geometry/vpTriangle.cpp b/modules/core/src/tools/geometry/vpTriangle.cpp index eeea8cd25f..9b979ddf97 100644 --- a/modules/core/src/tools/geometry/vpTriangle.cpp +++ b/modules/core/src/tools/geometry/vpTriangle.cpp @@ -102,9 +102,7 @@ vpTriangle &vpTriangle::operator=(const vpTriangle &tri) return *this; }; -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const vpImagePoint &, const vpImagePoint &, const vpImagePoint &) instead. Initialise the triangle thanks to the three 2D points \f$ iP1 \f$, \f$ iP2 \f$ and \f$ iP3 \f$ @@ -112,21 +110,7 @@ vpTriangle &vpTriangle::operator=(const vpTriangle &tri) \param iP2 : The first apex of the triangle. \param iP3 : The first apex of the triangle. */ -void vpTriangle::buildFrom(const vpImagePoint &iP1, const vpImagePoint &iP2, const vpImagePoint &iP3) -{ - build(iP1, iP2, iP3); -} -#endif - -/*! - Initialise the triangle thanks to the three 2D points \f$ iP1 \f$, \f$ iP2 - \f$ and \f$ iP3 \f$ - - \param iP1 : The first apex of the triangle. - \param iP2 : The first apex of the triangle. - \param iP3 : The first apex of the triangle. -*/ -vpTriangle &vpTriangle::build(const vpImagePoint &iP1, const vpImagePoint &iP2, const vpImagePoint &iP3) +vpTriangle &vpTriangle::buildFrom(const vpImagePoint &iP1, const vpImagePoint &iP2, const vpImagePoint &iP3) { init(iP1, iP2, iP3); return *this; diff --git a/modules/core/test/math/catchMatrixCholesky.cpp b/modules/core/test/math/catchMatrixCholesky.cpp index d6d2e21e3d..391ca816ba 100644 --- a/modules/core/test/math/catchMatrixCholesky.cpp +++ b/modules/core/test/math/catchMatrixCholesky.cpp @@ -130,7 +130,7 @@ TEST_CASE("3 x 3 input", "[cholesky]") SECTION("LAPACK") { vpMatrix L = M.choleskyByLapack(); - CHECK(testCholeskyDecomposition(M, gtL, L, "Test 1 Cholesky's decomposition using Lapack", true)); + CHECK(testCholeskyDecomposition(M, gtL, L, "Test Cholesky's decomposition using Lapack", true)); } #endif @@ -142,7 +142,9 @@ TEST_CASE("3 x 3 input", "[cholesky]") } #endif -#if defined(VISP_HAVE_OPENCV) +// There is a bug with OpenCV 3.1.0 +// See https://answers.opencv.org/question/99704/cholesky-function-in-opencv/ +#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION != 0x030100) SECTION("OPENCV") { vpMatrix L = M.choleskyByOpenCV(); @@ -169,7 +171,7 @@ TEST_CASE("4 x 4 input", "[cholesky]") SECTION("LAPACK") { vpMatrix L = M.choleskyByLapack(); - CHECK(testCholeskyDecomposition(M, gtL, L, "Test 1 Cholesky's decomposition using Lapack", true)); + CHECK(testCholeskyDecomposition(M, gtL, L, "Test Cholesky's decomposition using Lapack", true)); } #endif @@ -181,7 +183,9 @@ TEST_CASE("4 x 4 input", "[cholesky]") } #endif -#if defined(VISP_HAVE_OPENCV) +// There is a bug with OpenCV 3.1.0 +// See https://answers.opencv.org/question/99704/cholesky-function-in-opencv/ +#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION != 0x030100) SECTION("OPENCV") { vpMatrix L = M.choleskyByOpenCV(); diff --git a/modules/core/test/math/catchPoseVector.cpp b/modules/core/test/math/catchPoseVector.cpp index f510e94f3e..0478bc6bad 100644 --- a/modules/core/test/math/catchPoseVector.cpp +++ b/modules/core/test/math/catchPoseVector.cpp @@ -164,7 +164,7 @@ TEST_CASE("vpPoseVector build t, tu", "[vpColVector]") vpThetaUVector tu(ref[3], ref[4], ref[5]); vpPoseVector pose; - pose.build(t, tu); + pose.buildFrom(t, tu); checkSize(pose, ref); checkData(pose, ref); @@ -191,7 +191,7 @@ TEST_CASE("vpPoseVector build vpHomogeneousMatrix", "[vpColVector]") vpHomogeneousMatrix M(t, tu); vpPoseVector pose; - pose.build(M); + pose.buildFrom(M); checkSize(pose, ref); checkData(pose, ref); @@ -218,7 +218,7 @@ TEST_CASE("vpPoseVector build t, R", "[vpColVector]") vpRotationMatrix R(tu); vpPoseVector pose; - pose.build(t, R); + pose.buildFrom(t, R); checkSize(pose, ref); checkData(pose, ref); diff --git a/modules/core/test/math/catchRotation.cpp b/modules/core/test/math/catchRotation.cpp index 68bd59ab98..4d11283874 100644 --- a/modules/core/test/math/catchRotation.cpp +++ b/modules/core/test/math/catchRotation.cpp @@ -143,7 +143,7 @@ TEST_CASE("Common rotation operations", "[rotation]") bench1 = r1.toStdVector(); CHECK(test("r1", r1, bench1)); - r1.build(bench3); + r1.buildFrom(bench3); CHECK(test("r1", r1, bench3)); vpThetaUVector r2 = r1; @@ -178,7 +178,7 @@ TEST_CASE("Common rotation operations", "[rotation]") bench1 = r1.toStdVector(); CHECK(test("r1", r1, bench1)); - r1.build(bench3); + r1.buildFrom(bench3); CHECK(test("r1", r1, bench3)); vpRxyzVector r2 = r1; @@ -212,7 +212,7 @@ TEST_CASE("Common rotation operations", "[rotation]") bench1 = r1.toStdVector(); CHECK(test("r1", r1, bench1)); - r1.build(bench3); + r1.buildFrom(bench3); CHECK(test("r1", r1, bench3)); vpRzyxVector r2 = r1; @@ -246,7 +246,7 @@ TEST_CASE("Common rotation operations", "[rotation]") bench1 = r1.toStdVector(); CHECK(test("r1", r1, bench1)); - r1.build(bench3); + r1.buildFrom(bench3); CHECK(test("r1", r1, bench3)); vpRzyzVector r2 = r1; @@ -280,7 +280,7 @@ TEST_CASE("Common rotation operations", "[rotation]") bench1 = r1.toStdVector(); CHECK(test("r1", r1, bench1)); - r1.build(bench3); + r1.buildFrom(bench3); CHECK(test("r1", r1, bench3)); vpQuaternionVector r2 = r1; @@ -309,7 +309,7 @@ TEST_CASE("Common rotation operations", "[rotation]") for (int i = -10; i < 10; i++) { for (int j = -10; j < 10; j++) { vpThetaUVector tu(vpMath::rad(90 + i), vpMath::rad(170 + j), vpMath::rad(45)); - tu.build(vpRotationMatrix(tu)); // put some coherence into rotation convention + tu.buildFrom(vpRotationMatrix(tu)); // put some coherence into rotation convention std::cout << "Initialization " << std::endl; @@ -321,7 +321,7 @@ TEST_CASE("Common rotation operations", "[rotation]") std::cout << "u=" << u << std::endl; std::cout << "From vpThetaUVector to vpRotationMatrix " << std::endl; - R.build(tu); + R.buildFrom(tu); std::cout << "Matrix R"; CHECK(R.isARotationMatrix()); @@ -333,7 +333,7 @@ TEST_CASE("Common rotation operations", "[rotation]") CHECK(q.magnitude() == Catch::Approx(1.0).margin(1e-4)); std::cout << q << std::endl; - R.build(q); + R.buildFrom(q); CHECK(R.isARotationMatrix()); std::cout << "From vpQuaternionVector to vpRotationMatrix " << std::endl; @@ -346,7 +346,7 @@ TEST_CASE("Common rotation operations", "[rotation]") std::cout << " use From vpRotationMatrix to vpThetaUVector " << std::endl; vpThetaUVector tubuildEu; - tubuildEu.build(R); + tubuildEu.buildFrom(R); std::cout << std::endl; std::cout << "result : should equivalent to the first one " << std::endl; @@ -370,11 +370,11 @@ TEST_CASE("Common rotation operations", "[rotation]") std::cout << "Initialization vpRzyzVector " << std::endl; std::cout << rzyz << std::endl; std::cout << "From vpRzyzVector to vpRotationMatrix " << std::endl; - R.build(rzyz); + R.buildFrom(rzyz); CHECK(R.isARotationMatrix()); std::cout << "From vpRotationMatrix to vpRzyzVector " << std::endl; vpRzyzVector rzyz_final; - rzyz_final.build(R); + rzyz_final.buildFrom(R); CHECK(test("rzyz", rzyz_final, vpColVector(rzyz))); std::cout << rzyz_final << std::endl; } @@ -384,12 +384,12 @@ TEST_CASE("Common rotation operations", "[rotation]") std::cout << "Initialization vpRzyxVector " << std::endl; std::cout << rzyx << std::endl; std::cout << "From vpRzyxVector to vpRotationMatrix " << std::endl; - R.build(rzyx); + R.buildFrom(rzyx); CHECK(R.isARotationMatrix()); std::cout << R << std::endl; std::cout << "From vpRotationMatrix to vpRzyxVector " << std::endl; vpRzyxVector rzyx_final; - rzyx_final.build(R); + rzyx_final.buildFrom(R); bool ret = test("rzyx", rzyx_final, vpColVector(rzyx)); if (ret == false) { // Euler angle representation is not unique diff --git a/modules/core/test/tools/geometry/catchPolygon2.cpp b/modules/core/test/tools/geometry/catchPolygon2.cpp index 9813e074cd..48f243cb0b 100644 --- a/modules/core/test/tools/geometry/catchPolygon2.cpp +++ b/modules/core/test/tools/geometry/catchPolygon2.cpp @@ -59,7 +59,7 @@ TEST_CASE("Check polygon construction") rect.getBottomLeft() }; vpPolygon poly {}; - poly.build(rect_corners, true); + poly.buildFrom(rect_corners, true); // Check if std:c++14 or higher #if ((__cplusplus >= 201402L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201402L))) @@ -71,8 +71,8 @@ TEST_CASE("Check polygon construction") REQUIRE(std::find(begin(rect_corners), end(rect_corners), poly_corner) != end(rect_corners)); } #endif - } } +} int main(int argc, char *argv[]) { diff --git a/modules/core/test/tools/geometry/testPolygon.cpp b/modules/core/test/tools/geometry/testPolygon.cpp index ecefcab6a1..9e45bd414e 100644 --- a/modules/core/test/tools/geometry/testPolygon.cpp +++ b/modules/core/test/tools/geometry/testPolygon.cpp @@ -174,7 +174,7 @@ int main(int argc, const char **argv) vec1.push_back(vpImagePoint(380, 300)); vec1.push_back(vpImagePoint(280, 280)); vpPolygon p1; - p1.build(vec1); + p1.buildFrom(vec1); std::vector vec2; vec2.push_back(vpImagePoint(20, 20)); diff --git a/modules/detection/CMakeLists.txt b/modules/detection/CMakeLists.txt index 6c31031f61..8e289ebd9f 100644 --- a/modules/detection/CMakeLists.txt +++ b/modules/detection/CMakeLists.txt @@ -201,3 +201,7 @@ if(WITH_CATCH2) endif() vp_add_tests(DEPENDS_ON visp_detection visp_gui visp_io PRIVATE_INCLUDE_DIRS ${opt_test_incs} PRIVATE_LIBRARIES ${opt_test_libs}) + +if(WIN32) + vp_set_source_file_compile_flag(src/tag/vpDetectorAprilTag.cpp /wd4244) +endif() diff --git a/modules/gui/src/plot/vpPlotGraph.cpp b/modules/gui/src/plot/vpPlotGraph.cpp index ef3aa7c5eb..16cf7ad820 100644 --- a/modules/gui/src/plot/vpPlotGraph.cpp +++ b/modules/gui/src/plot/vpPlotGraph.cpp @@ -153,7 +153,7 @@ void vpPlotGraph::initSize(vpImagePoint top_left, unsigned int w, unsigned int h findPose(); - cMf.build(0, 0, cMo[2][3], 0, 0, 0); + cMf.buildFrom(0, 0, cMo[2][3], 0, 0, 0); } void vpPlotGraph::findPose() @@ -1322,7 +1322,7 @@ vpHomogeneousMatrix vpPlotGraph::navigation(const vpImage &I, boo double anglei = diffi * 360 / width_; double anglej = diffj * 360 / width_; - mov.build(0, 0, 0, vpMath::rad(anglei), vpMath::rad(-anglej), 0); + mov.buildFrom(0, 0, 0, vpMath::rad(anglei), vpMath::rad(-anglej), 0); changed = true; } @@ -1331,7 +1331,7 @@ vpHomogeneousMatrix vpPlotGraph::navigation(const vpImage &I, boo if (old_iPz != vpImagePoint(-1, -1) && blockedz) { double diffi = iP.get_i() - old_iPz.get_i(); - mov.build(0, 0, diffi * 0.01, 0, 0, 0); + mov.buildFrom(0, 0, diffi * 0.01, 0, 0, 0); changed = true; } diff --git a/modules/gui/test/display/testDisplays.cpp b/modules/gui/test/display/testDisplays.cpp index e7ca90dad9..308dfb48c0 100644 --- a/modules/gui/test/display/testDisplays.cpp +++ b/modules/gui/test/display/testDisplays.cpp @@ -273,7 +273,7 @@ template static void draw(vpImage &I) vip.push_back(vpImagePoint(350, 350)); vip.push_back(vpImagePoint(400, 300)); vip.push_back(vpImagePoint(350, 250)); - polygon.build(vip); + polygon.buildFrom(vip); vpDisplay::displayPolygon(I, polygon, vpColor::cyan, 3, false); } diff --git a/modules/io/test/catchJsonArgumentParser.cpp b/modules/io/test/catchJsonArgumentParser.cpp index 0b78faee46..b9d6089fe2 100644 --- a/modules/io/test/catchJsonArgumentParser.cpp +++ b/modules/io/test/catchJsonArgumentParser.cpp @@ -295,7 +295,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") REQUIRE_THROWS(vpJsonArgumentParser("A program", "", "/")); } - WHEN("Instanciating a parser with some optional fields") + WHEN("Instantiating a parser with some optional fields") { vpJsonArgumentParser parser("A program", "--config", "/"); float b = 0.0; @@ -314,7 +314,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") } } - WHEN("Instanciating a parser with nested parameters") + WHEN("Instantiating a parser with nested parameters") { vpJsonArgumentParser parser("A program", "--config", "/"); float b = 0.0; @@ -335,7 +335,7 @@ SCENARIO("Parsing arguments from JSON file", "[json]") } - WHEN("Instanciating a parser with some documentation") + WHEN("Instantiating a parser with some documentation") { const std::string programString = "ProgramString"; const std::string firstArg = "FirstArgName", firstArgDescription = "FirstArgDescription"; diff --git a/modules/python/examples/ibvs-four-points.py b/modules/python/examples/ibvs-four-points.py index 87487c457f..aa73828db7 100644 --- a/modules/python/examples/ibvs-four-points.py +++ b/modules/python/examples/ibvs-four-points.py @@ -278,7 +278,7 @@ def display(self, fig_filename): if not args.no_plot: for f in x: p = FeaturePoint() - p.build(f.get_x(), f.get_y(), f.get_Z()) + p.buildFrom(f.get_x(), f.get_y(), f.get_Z()) xplot.append(p) if iter == 0: diff --git a/modules/python/examples/pbvs-four-points.py b/modules/python/examples/pbvs-four-points.py index 0b21e1885d..0a06bb979d 100644 --- a/modules/python/examples/pbvs-four-points.py +++ b/modules/python/examples/pbvs-four-points.py @@ -244,8 +244,8 @@ def display(self, fig_filename): # Compute current features cd_T_c = cd_T_w * c_T_w.inverse() - t.build(cd_T_c) - tu.build(cd_T_c) + t.buildFrom(cd_T_c) + tu.buildFrom(cd_T_c) # Begin just for point trajectory display, compute the coordinates of the points in the image plane for i in range(len(wX)): diff --git a/modules/python/examples/yolo-centering-task-afma6.py b/modules/python/examples/yolo-centering-task-afma6.py index 4844b185c2..36efd4aeb8 100644 --- a/modules/python/examples/yolo-centering-task-afma6.py +++ b/modules/python/examples/yolo-centering-task-afma6.py @@ -255,10 +255,10 @@ def animate(i): Zd = I_depth[h // 2, w // 2] * depth_scale print(f'Desired depth is {Zd}') sd = FeaturePoint() - sd.build(xd, yd, Zd) + sd.buildFrom(xd, yd, Zd) s = FeaturePoint() - s.build(0.0, 0.0, Zd) + s.buildFrom(0.0, 0.0, Zd) task = Servo() task.addFeature(s, sd) @@ -309,14 +309,14 @@ def has_class_box(box): kalman.filter(ColVector([x, y]), (1 / fps)) kalman_state = kalman.getXest() last_detection_time = time.time() - s.build(kalman_state[0], kalman_state[3], Zd) + s.buildFrom(kalman_state[0], kalman_state[3], Zd) v = task.computeControlLaw() else: if last_detection_time < 0.0: raise RuntimeError('No detection at first iteration') kalman.predict(time.time() - last_detection_time) kalman_pred = kalman.getXpred() - s.build(kalman_pred[0], kalman_pred[3], Zd) + s.buildFrom(kalman_pred[0], kalman_pred[3], Zd) task.computeControlLaw() error: ColVector = task.getError() @@ -333,7 +333,7 @@ def has_class_box(box): Display.flush(I) Display.getImage(I, Idisp) robot.getPosition(Robot.ControlFrameType.REFERENCE_FRAME, r) - cTw.build(r) + cTw.buildFrom(r) plotter.on_iter(Idisp, v, error, cTw) # Move robot/update simulator diff --git a/modules/python/examples/yolo-centering-task.py b/modules/python/examples/yolo-centering-task.py index 06ed1b08ed..1d91c53d3e 100644 --- a/modules/python/examples/yolo-centering-task.py +++ b/modules/python/examples/yolo-centering-task.py @@ -125,10 +125,10 @@ def animate(i): # Define centering task xd, yd = PixelMeterConversion.convertPoint(cam, w / 2.0, h / 2.0) sd = FeaturePoint() - sd.build(xd, yd, Z) + sd.buildFrom(xd, yd, Z) s = FeaturePoint() - s.build(0.0, 0.0, Z) + s.buildFrom(0.0, 0.0, Z) task = Servo() task.addFeature(s, sd) @@ -177,7 +177,7 @@ def has_class_box(box): if bb is not None: u, v = bb[0], bb[1] x, y = PixelMeterConversion.convertPoint(cam, u, v) - s.build(x, y, Z) + s.buildFrom(x, y, Z) v = task.computeControlLaw() prev_v = v else: diff --git a/modules/robot/include/visp3/robot/vpPioneer.h b/modules/robot/include/visp3/robot/vpPioneer.h index 28ac2962a8..d2f8810272 100644 --- a/modules/robot/include/visp3/robot/vpPioneer.h +++ b/modules/robot/include/visp3/robot/vpPioneer.h @@ -107,8 +107,8 @@ class VISP_EXPORT vpPioneer : public vpUnicycle vpTranslationVector cte; // meters vpRxyzVector cre; // radian cte.set(0, 0, -l); - cre.build(vpMath::rad(90.), 0, vpMath::rad(90.)); - cMe_.build(cte, vpRotationMatrix(cre)); + cre.buildFrom(vpMath::rad(90.), 0, vpMath::rad(90.)); + cMe_.buildFrom(cte, vpRotationMatrix(cre)); } /*! diff --git a/modules/robot/include/visp3/robot/vpPioneerPan.h b/modules/robot/include/visp3/robot/vpPioneerPan.h index 23bf29fb44..6a8b1d8486 100644 --- a/modules/robot/include/visp3/robot/vpPioneerPan.h +++ b/modules/robot/include/visp3/robot/vpPioneerPan.h @@ -175,7 +175,7 @@ class VISP_EXPORT vpPioneerPan : public vpUnicycle eRc[2][0] = -1; vpHomogeneousMatrix eMc; - eMc.build(etc, eRc); + eMc.buildFrom(etc, eRc); cMe_ = eMc.inverse(); } diff --git a/modules/robot/include/visp3/robot/vpRobotFranka.h b/modules/robot/include/visp3/robot/vpRobotFranka.h index a440313e1a..bcac458aef 100644 --- a/modules/robot/include/visp3/robot/vpRobotFranka.h +++ b/modules/robot/include/visp3/robot/vpRobotFranka.h @@ -162,7 +162,7 @@ BEGIN_VISP_NAMESPACE * vpHomogeneousMatrix wMe; * while(1) { * robot.getPosition(vpRobot::END_EFFECTOR_FRAME, wPe); - * wMe.build(wPe); + * wMe.buildFrom(wPe); * ... * } * \endcode @@ -177,7 +177,7 @@ BEGIN_VISP_NAMESPACE * vpHomogeneousMatrix wMc; * while(1) { * robot.getPosition(vpRobot::CAMERA_FRAME, wPc); - * wMc.build(wPc); + * wMc.buildFrom(wPc); * ... * } * \endcode @@ -192,7 +192,7 @@ BEGIN_VISP_NAMESPACE * vpHomogeneousMatrix wMt; * while(1) { * robot.getPosition(vpRobot::TOOL_FRAME, wPt); - * wMt.build(wPt); + * wMt.buildFrom(wPt); * ... * } * \endcode diff --git a/modules/robot/include/visp3/robot/vpUnicycle.h b/modules/robot/include/visp3/robot/vpUnicycle.h index d36f4c628e..df5c5ae9d6 100644 --- a/modules/robot/include/visp3/robot/vpUnicycle.h +++ b/modules/robot/include/visp3/robot/vpUnicycle.h @@ -72,7 +72,7 @@ class VISP_EXPORT vpUnicycle vpVelocityTwistMatrix get_cVe() const { vpVelocityTwistMatrix cVe; - cVe.build(cMe_); + cVe.buildFrom(cMe_); return cVe; } diff --git a/modules/robot/include/visp3/robot/vpWireFrameSimulator.h b/modules/robot/include/visp3/robot/vpWireFrameSimulator.h index 8c95d05041..052a2e1934 100644 --- a/modules/robot/include/visp3/robot/vpWireFrameSimulator.h +++ b/modules/robot/include/visp3/robot/vpWireFrameSimulator.h @@ -553,7 +553,7 @@ class VISP_EXPORT vpWireFrameSimulator this->camMf = rotz * cam_Mf; vpTranslationVector T; this->camMf.extract(T); - this->camMf2.build(0, 0, T[2], 0, 0, 0); + this->camMf2.buildFrom(0, 0, T[2], 0, 0, 0); f2Mf = camMf2.inverse() * this->camMf; extCamChanged = true; } diff --git a/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp b/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp index 7e9098c22e..67e1e45b1e 100644 --- a/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp +++ b/modules/robot/src/haptic-device/virtuose/vpVirtuose.cpp @@ -205,7 +205,7 @@ vpPoseVector vpVirtuose::getAvatarPosition() const vpThetaUVector thetau(quaternion); - position.build(translation, thetau); + position.buildFrom(translation, thetau); return position; } @@ -240,7 +240,7 @@ vpPoseVector vpVirtuose::getBaseFrame() const vpThetaUVector thetau(quaternion); - position.build(translation, thetau); + position.buildFrom(translation, thetau); return position; } @@ -404,7 +404,7 @@ vpPoseVector vpVirtuose::getObservationFrame() const vpThetaUVector thetau(quaternion); - position.build(translation, thetau); + position.buildFrom(translation, thetau); } return position; } @@ -438,7 +438,7 @@ vpPoseVector vpVirtuose::getPhysicalPosition() const vpThetaUVector thetau(quaternion); - position.build(translation, thetau); + position.buildFrom(translation, thetau); } return position; } @@ -495,7 +495,7 @@ vpPoseVector vpVirtuose::getPosition() const vpThetaUVector thetau(quaternion); - position.build(translation, thetau); + position.buildFrom(translation, thetau); } return position; } diff --git a/modules/robot/src/real-robot/afma4/vpAfma4.cpp b/modules/robot/src/real-robot/afma4/vpAfma4.cpp index 58a63de5fd..2777d73310 100644 --- a/modules/robot/src/real-robot/afma4/vpAfma4.cpp +++ b/modules/robot/src/real-robot/afma4/vpAfma4.cpp @@ -92,7 +92,7 @@ vpAfma4::vpAfma4() : _a1(0), _d3(0), _d4(0), _etc(), _erc(), _eMc() this->_erc[2] = 0; vpRotationMatrix eRc(_erc); - this->_eMc.build(_etc, eRc); + this->_eMc.buildFrom(_etc, eRc); init(); } @@ -320,7 +320,7 @@ void vpAfma4::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); return; } @@ -349,7 +349,7 @@ void vpAfma4::get_cVf(const vpColVector &q, vpVelocityTwistMatrix &cVf) const get_fMc(q, fMc); cMf = fMc.inverse(); - cVf.build(cMf); + cVf.buildFrom(cMf); return; } diff --git a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp index 908c7fe7e7..5d29b8ceae 100644 --- a/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp +++ b/modules/robot/src/real-robot/afma4/vpRobotAfma4.cpp @@ -531,7 +531,7 @@ void vpRobotAfma4::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; vpAfma4::get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); } /*! @@ -1035,7 +1035,7 @@ void vpRobotAfma4::getPosition(const vpRobot::vpControlFrameType frame, vpColVec vpRotationMatrix fRc; fMc.extract(fRc); vpRxyzVector rxyz; - rxyz.build(fRc); + rxyz.buildFrom(fRc); for (unsigned int i = 0; i < 3; i++) { position[i] = fMc[i][3]; // translation x,y,z @@ -1221,7 +1221,7 @@ void vpRobotAfma4::setVelocity(const vpRobot::vpControlFrameType frame, const vp // Transform the velocities from camera to end-effector frame vpVelocityTwistMatrix eVc; - eVc.build(this->_eMc); + eVc.buildFrom(this->_eMc); joint_vel = eJe_inverse * eVc * velocity; // printf("Vitesse art: %f %f %f %f\n", joint_vel[0], joint_vel[1], diff --git a/modules/robot/src/real-robot/afma6/vpAfma6.cpp b/modules/robot/src/real-robot/afma6/vpAfma6.cpp index 344d05115d..a2340c1059 100644 --- a/modules/robot/src/real-robot/afma6/vpAfma6.cpp +++ b/modules/robot/src/real-robot/afma6/vpAfma6.cpp @@ -485,7 +485,7 @@ void vpAfma6::init(vpAfma6::vpAfma6ToolType tool, vpCameraParameters::vpCameraPa } } vpRotationMatrix eRc(_erc); - this->_eMc.build(_etc, eRc); + this->_eMc.buildFrom(_etc, eRc); #endif // VISP_HAVE_AFMA6_DATA setToolType(tool); @@ -921,7 +921,7 @@ void vpAfma6::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); return; } @@ -1181,7 +1181,7 @@ void vpAfma6::parseConfigFile(const std::string &filename) _etc = etc; vpRotationMatrix eRc(_erc); - this->_eMc.build(_etc, eRc); + this->_eMc.buildFrom(_etc, eRc); } } @@ -1199,7 +1199,7 @@ void vpAfma6::set_eMc(const vpHomogeneousMatrix &eMc) this->_etc = eMc.getTranslationVector(); vpRotationMatrix R(eMc); - this->_erc.build(R); + this->_erc.buildFrom(R); } /*! diff --git a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp index 7c105910ed..14eeddbbdc 100644 --- a/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp +++ b/modules/robot/src/real-robot/afma6/vpRobotAfma6.cpp @@ -808,7 +808,7 @@ void vpRobotAfma6::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; vpAfma6::get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); } /*! @@ -1022,8 +1022,8 @@ void vpRobotAfma6::setPosition(const vpRobot::vpControlFrameType frame, const vp vpRxyzVector rxyz; vpRotationMatrix R; - R.build(pose[3], pose[4], pose[5]); // thetau - rxyz.build(R); + R.buildFrom(pose[3], pose[4], pose[5]); // thetau + rxyz.buildFrom(R); for (unsigned int i = 0; i < 3; i++) { position[i] = pose[i]; @@ -1484,7 +1484,7 @@ void vpRobotAfma6::getPosition(const vpRobot::vpControlFrameType frame, vpColVec vpRotationMatrix fRc; fMc.extract(fRc); vpRxyzVector rxyz; - rxyz.build(fRc); + rxyz.buildFrom(fRc); for (unsigned int i = 0; i < 3; i++) { position[i] = fMc[i][3]; // translation x,y,z @@ -1841,7 +1841,7 @@ void vpRobotAfma6::getVelocity(const vpRobot::vpControlFrameType frame, vpColVec vpRotationMatrix cRc; cMc.extract(cRc); vpThetaUVector thetaU; - thetaU.build(cRc); + thetaU.buildFrom(cRc); for (unsigned int i = 0; i < 3; i++) { // Compute the translation displacement in the reference frame @@ -2248,7 +2248,7 @@ void vpRobotAfma6::getDisplacement(vpRobot::vpControlFrameType frame, vpColVecto c_prevMc_cur.extract(R); vpRxyzVector rxyz; - rxyz.build(R); + rxyz.buildFrom(R); for (unsigned int i = 0; i < 3; i++) { displacement[i] = t[i]; diff --git a/modules/robot/src/real-robot/biclops/vpBiclops.cpp b/modules/robot/src/real-robot/biclops/vpBiclops.cpp index 5886148d85..60b5e81a47 100644 --- a/modules/robot/src/real-robot/biclops/vpBiclops.cpp +++ b/modules/robot/src/real-robot/biclops/vpBiclops.cpp @@ -149,7 +149,7 @@ void vpBiclops::computeMGD(const vpColVector &q, vpPoseVector &fPc) const vpHomogeneousMatrix fMc; get_fMc(q, fMc); - fPc.build(fMc.inverse()); + fPc.buildFrom(fMc.inverse()); return; } @@ -159,7 +159,7 @@ void vpBiclops::get_fMc(const vpColVector &q, vpPoseVector &fPc) const vpHomogeneousMatrix fMc; get_fMc(q, fMc); - fPc.build(fMc.inverse()); + fPc.buildFrom(fMc.inverse()); return; } @@ -182,7 +182,7 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpBiclops & /*const return os; } -void vpBiclops::get_cVe(vpVelocityTwistMatrix &cVe) const { cVe.build(m_cMe); } +void vpBiclops::get_cVe(vpVelocityTwistMatrix &cVe) const { cVe.buildFrom(m_cMe); } void vpBiclops::set_cMe() { diff --git a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp index 80e4a1536c..10facce3f1 100644 --- a/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp +++ b/modules/robot/src/real-robot/biclops/vpRobotBiclops.cpp @@ -432,7 +432,7 @@ void vpRobotBiclops::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; cMe = vpBiclops::get_cMe(); - cVe.build(cMe); + cVe.buildFrom(cMe); } void vpRobotBiclops::get_cMe(vpHomogeneousMatrix &cMe) const { cMe = vpBiclops::get_cMe(); } diff --git a/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp b/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp index 27b57c2a03..08f12b43db 100644 --- a/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp +++ b/modules/robot/src/real-robot/flir-ptu/vpRobotFlirPtu.cpp @@ -237,7 +237,7 @@ vpMatrix vpRobotFlirPtu::get_fMe() vpVelocityTwistMatrix vpRobotFlirPtu::get_cVe() const { vpVelocityTwistMatrix cVe; - cVe.build(m_eMc.inverse()); + cVe.buildFrom(m_eMc.inverse()); return cVe; } diff --git a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp index 7a265389fe..bfcc2de660 100644 --- a/modules/robot/src/real-robot/franka/vpRobotFranka.cpp +++ b/modules/robot/src/real-robot/franka/vpRobotFranka.cpp @@ -455,11 +455,11 @@ void vpRobotFranka::getPosition(const vpRobot::vpControlFrameType frame, vpPoseV switch (frame) { case END_EFFECTOR_FRAME: { - pose.build(fMe); + pose.buildFrom(fMe); break; } case TOOL_FRAME: { - pose.build(fMe * m_eMc); + pose.buildFrom(fMe * m_eMc); break; } default: { diff --git a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp index b6bc4b3940..d78b35b3c2 100644 --- a/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp +++ b/modules/robot/src/real-robot/mavsdk/vpRobotMavsdk.cpp @@ -295,7 +295,7 @@ class vpRobotMavsdk::vpRobotMavsdkImpl auto posvel = m_telemetry.get()->position_velocity_ned(); vpQuaternionVector q { quat.x, quat.y, quat.z, quat.w }; vpTranslationVector t { posvel.position.north_m, posvel.position.east_m, posvel.position.down_m }; - ned_M_frd.build(t, q); + ned_M_frd.buildFrom(t, q); } void getPosition(float &ned_north, float &ned_east, float &ned_down, float &ned_yaw) const diff --git a/modules/robot/src/real-robot/ptu46/vpPtu46.cpp b/modules/robot/src/real-robot/ptu46/vpPtu46.cpp index e5b7600a43..9ab81dbd78 100644 --- a/modules/robot/src/real-robot/ptu46/vpPtu46.cpp +++ b/modules/robot/src/real-robot/ptu46/vpPtu46.cpp @@ -138,7 +138,7 @@ void vpPtu46::computeMGD(const vpColVector &q, vpPoseVector &r) const vpHomogeneousMatrix fMc; computeMGD(q, fMc); - r.build(fMc.inverse()); + r.buildFrom(fMc.inverse()); return; } @@ -193,7 +193,7 @@ void vpPtu46::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); } /*! diff --git a/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp b/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp index 67c6374206..a7b715b9ce 100644 --- a/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp +++ b/modules/robot/src/real-robot/ptu46/vpRobotPtu46.cpp @@ -207,7 +207,7 @@ void vpRobotPtu46::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; vpPtu46::get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); } /*! diff --git a/modules/robot/src/real-robot/viper/vpRobotViper650.cpp b/modules/robot/src/real-robot/viper/vpRobotViper650.cpp index e478d30b04..1c679d06dc 100644 --- a/modules/robot/src/real-robot/viper/vpRobotViper650.cpp +++ b/modules/robot/src/real-robot/viper/vpRobotViper650.cpp @@ -922,7 +922,7 @@ void vpRobotViper650::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; vpViper650::get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); } /*! @@ -1502,7 +1502,7 @@ void vpRobotViper650::getPosition(const vpRobot::vpControlFrameType frame, vpCol vpRotationMatrix fRc; fMc.extract(fRc); vpRxyzVector rxyz; - rxyz.build(fRc); + rxyz.buildFrom(fRc); for (unsigned int i = 0; i < 3; i++) { position[i] = fMc[i][3]; // translation x,y,z @@ -1940,7 +1940,7 @@ void vpRobotViper650::getVelocity(const vpRobot::vpControlFrameType frame, vpCol vpRotationMatrix cRc; cMc.extract(cRc); vpThetaUVector thetaU; - thetaU.build(cRc); + thetaU.buildFrom(cRc); for (unsigned int i = 0; i < 3; i++) { // Compute the translation displacement in the reference frame diff --git a/modules/robot/src/real-robot/viper/vpRobotViper850.cpp b/modules/robot/src/real-robot/viper/vpRobotViper850.cpp index 05e32a6983..ce0896b3f9 100644 --- a/modules/robot/src/real-robot/viper/vpRobotViper850.cpp +++ b/modules/robot/src/real-robot/viper/vpRobotViper850.cpp @@ -942,7 +942,7 @@ void vpRobotViper850::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; vpViper850::get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); } /*! @@ -1521,7 +1521,7 @@ void vpRobotViper850::getPosition(const vpRobot::vpControlFrameType frame, vpCol vpRotationMatrix fRc; fMc.extract(fRc); vpRxyzVector rxyz; - rxyz.build(fRc); + rxyz.buildFrom(fRc); for (unsigned int i = 0; i < 3; i++) { position[i] = fMc[i][3]; // translation x,y,z @@ -1971,7 +1971,7 @@ void vpRobotViper850::getVelocity(const vpRobot::vpControlFrameType frame, vpCol vpRotationMatrix cRc; cMc.extract(cRc); vpThetaUVector thetaU; - thetaU.build(cRc); + thetaU.buildFrom(cRc); for (unsigned int i = 0; i < 3; i++) { // Compute the translation displacement in the reference frame diff --git a/modules/robot/src/real-robot/viper/vpViper.cpp b/modules/robot/src/real-robot/viper/vpViper.cpp index 151422bda8..0b21b34817 100644 --- a/modules/robot/src/real-robot/viper/vpViper.cpp +++ b/modules/robot/src/real-robot/viper/vpViper.cpp @@ -939,7 +939,7 @@ void vpViper::get_cVe(vpVelocityTwistMatrix &cVe) const vpHomogeneousMatrix cMe; get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); return; } @@ -1231,7 +1231,7 @@ void vpViper::set_eMc(const vpHomogeneousMatrix &eMc_) this->eMc = eMc_; this->eMc.extract(etc); vpRotationMatrix R(this->eMc); - this->erc.build(R); + this->erc.buildFrom(R); } /*! @@ -1249,7 +1249,7 @@ void vpViper::set_eMc(const vpTranslationVector &etc_, const vpRxyzVector &erc_) this->etc = etc_; this->erc = erc_; vpRotationMatrix eRc(erc); - this->eMc.build(etc, eRc); + this->eMc.buildFrom(etc, eRc); } /*! diff --git a/modules/robot/src/real-robot/viper/vpViper650.cpp b/modules/robot/src/real-robot/viper/vpViper650.cpp index fe3b27073a..ce58802d97 100644 --- a/modules/robot/src/real-robot/viper/vpViper650.cpp +++ b/modules/robot/src/real-robot/viper/vpViper650.cpp @@ -340,7 +340,7 @@ void vpViper650::init(vpViper650::vpToolType tool, vpCameraParameters::vpCameraP } } vpRotationMatrix eRc(erc); - this->eMc.build(etc, eRc); + this->eMc.buildFrom(etc, eRc); #endif // VISP_HAVE_VIPER650_DATA setToolType(tool); diff --git a/modules/robot/src/real-robot/viper/vpViper850.cpp b/modules/robot/src/real-robot/viper/vpViper850.cpp index a7591b1704..a50b85c6c2 100644 --- a/modules/robot/src/real-robot/viper/vpViper850.cpp +++ b/modules/robot/src/real-robot/viper/vpViper850.cpp @@ -341,7 +341,7 @@ void vpViper850::init(vpViper850::vpToolType tool, vpCameraParameters::vpCameraP } } vpRotationMatrix eRc(erc); - this->eMc.build(etc, eRc); + this->eMc.buildFrom(etc, eRc); #endif // VISP_HAVE_VIPER850_DATA setToolType(tool); diff --git a/modules/robot/src/robot-simulator/vpRobotCamera.cpp b/modules/robot/src/robot-simulator/vpRobotCamera.cpp index a5638bd7cf..179722d98a 100644 --- a/modules/robot/src/robot-simulator/vpRobotCamera.cpp +++ b/modules/robot/src/robot-simulator/vpRobotCamera.cpp @@ -217,7 +217,7 @@ void vpRobotCamera::getPosition(const vpRobot::vpControlFrameType frame, vpColVe vpRotationMatrix cRw; this->cMw_.extract(cRw); vpRxyzVector rxyz; - rxyz.build(cRw); + rxyz.buildFrom(cRw); for (unsigned int i = 0; i < 3; i++) { q[i] = this->cMw_[i][3]; // translation x,y,z diff --git a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp index 971da0a4a0..c3f07c17d1 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorAfma6.cpp @@ -322,7 +322,7 @@ void vpSimulatorAfma6::init(vpAfma6::vpAfma6ToolType tool, vpCameraParameters::v vpRotationMatrix eRc(_erc); m_mutex_eMc.lock(); - this->_eMc.build(_etc, eRc); + this->_eMc.buildFrom(_etc, eRc); m_mutex_eMc.unlock(); setToolType(tool); @@ -2094,7 +2094,7 @@ void vpSimulatorAfma6::get_cVe(vpVelocityTwistMatrix &cVe) vpHomogeneousMatrix cMe; vpAfma6::get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); } /*! @@ -2468,7 +2468,7 @@ bool vpSimulatorAfma6::setPosition(const vpHomogeneousMatrix &cdMo_, vpImagewMc_.extract(wRc); vpRxyzVector rxyz; - rxyz.build(wRc); + rxyz.buildFrom(wRc); for (unsigned int i = 0; i < 3; i++) { q[i] = this->wMc_[i][3]; // translation x,y,z diff --git a/modules/robot/src/robot-simulator/vpSimulatorPioneer.cpp b/modules/robot/src/robot-simulator/vpSimulatorPioneer.cpp index 6f08e3b330..0e12d2f89b 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorPioneer.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorPioneer.cpp @@ -130,7 +130,7 @@ void vpSimulatorPioneer::setVelocity(const vpRobot::vpControlFrameType frame, co vpRotationMatrix wRe(0, 0, theta_); vpTranslationVector wte(xm_, ym_, 0); - wMe_.build(wte, wRe); + wMe_.buildFrom(wte, wRe); wMc_ = wMe_ * cMe_.inverse(); break; @@ -200,7 +200,7 @@ void vpSimulatorPioneer::getPosition(const vpRobot::vpControlFrameType frame, vp vpRotationMatrix wRc; this->wMc_.extract(wRc); vpRxyzVector rxyz; - rxyz.build(wRc); + rxyz.buildFrom(wRc); for (unsigned int i = 0; i < 3; i++) { q[i] = this->wMc_[i][3]; // translation x,y,z diff --git a/modules/robot/src/robot-simulator/vpSimulatorPioneerPan.cpp b/modules/robot/src/robot-simulator/vpSimulatorPioneerPan.cpp index a51ff81308..90a4bdf9d1 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorPioneerPan.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorPioneerPan.cpp @@ -142,7 +142,7 @@ void vpSimulatorPioneerPan::setVelocity(const vpRobot::vpControlFrameType frame, vpRotationMatrix wRm(0, 0, theta_); vpTranslationVector wtm(xm_, ym_, 0); - wMm_.build(wtm, wRm); + wMm_.buildFrom(wtm, wRm); // Update the end effector pose set_pMe(q_pan_); @@ -215,7 +215,7 @@ void vpSimulatorPioneerPan::getPosition(const vpRobot::vpControlFrameType frame, vpRotationMatrix wRc; this->wMc_.extract(wRc); vpRxyzVector rxyz; - rxyz.build(wRc); + rxyz.buildFrom(wRc); for (unsigned int i = 0; i < 3; i++) { q[i] = this->wMc_[i][3]; // translation x,y,z diff --git a/modules/robot/src/robot-simulator/vpSimulatorViper850.cpp b/modules/robot/src/robot-simulator/vpSimulatorViper850.cpp index d085f9f45e..9856c60fd4 100644 --- a/modules/robot/src/robot-simulator/vpSimulatorViper850.cpp +++ b/modules/robot/src/robot-simulator/vpSimulatorViper850.cpp @@ -263,7 +263,7 @@ void vpSimulatorViper850::init(vpViper850::vpToolType tool, vpCameraParameters:: vpRotationMatrix eRc(erc); m_mutex_eMc.lock(); - this->eMc.build(etc, eRc); + this->eMc.buildFrom(etc, eRc); m_mutex_eMc.unlock(); setToolType(tool); @@ -2087,7 +2087,7 @@ void vpSimulatorViper850::get_cVe(vpVelocityTwistMatrix &cVe) vpHomogeneousMatrix cMe; vpViper850::get_cMe(cMe); - cVe.build(cMe); + cVe.buildFrom(cMe); } /*! diff --git a/modules/robot/src/wireframe-simulator/vpWireFrameSimulator.cpp b/modules/robot/src/wireframe-simulator/vpWireFrameSimulator.cpp index 6e1615dd04..3954cae702 100644 --- a/modules/robot/src/wireframe-simulator/vpWireFrameSimulator.cpp +++ b/modules/robot/src/wireframe-simulator/vpWireFrameSimulator.cpp @@ -207,7 +207,7 @@ vpWireFrameSimulator::vpWireFrameSimulator() old_iPz = vpImagePoint(-1, -1); old_iPt = vpImagePoint(-1, -1); - rotz.build(0, 0, 0, 0, 0, vpMath::rad(180)); + rotz.buildFrom(0, 0, 0, 0, 0, vpMath::rad(180)); scene.name = NULL; scene.bound.ptr = NULL; @@ -1415,7 +1415,7 @@ vpHomogeneousMatrix vpWireFrameSimulator::navigation(const vpImage &I, b // cout << "delta :" << diffj << endl;; double anglei = diffi * 360 / width; double anglej = diffj * 360 / width; - mov.build(0, 0, 0, vpMath::rad(-anglei), vpMath::rad(anglej), 0); + mov.buildFrom(0, 0, 0, vpMath::rad(-anglei), vpMath::rad(anglej), 0); changed = true; } @@ -1424,7 +1424,7 @@ vpHomogeneousMatrix vpWireFrameSimulator::navigation(const vpImage &I, b if (old_iPz != vpImagePoint(-1, -1) && blockedz) { double diffi = iP.get_i() - old_iPz.get_i(); - mov.build(0, 0, diffi * 0.01, 0, 0, 0); + mov.buildFrom(0, 0, diffi * 0.01, 0, 0, 0); changed = true; } @@ -1434,7 +1434,7 @@ vpHomogeneousMatrix vpWireFrameSimulator::navigation(const vpImage &I, b if (old_iPt != vpImagePoint(-1, -1) && blockedt) { double diffi = iP.get_i() - old_iPt.get_i(); double diffj = iP.get_j() - old_iPt.get_j(); - mov.build(diffj * 0.01, diffi * 0.01, 0, 0, 0, 0); + mov.buildFrom(diffj * 0.01, diffi * 0.01, 0, 0, 0, 0); changed = true; } @@ -1506,7 +1506,7 @@ vpHomogeneousMatrix vpWireFrameSimulator::navigation(const vpImage(pose_data.rotation.x), static_cast(pose_data.rotation.y), static_cast(pose_data.rotation.z), static_cast(pose_data.rotation.w)); - cMw.build(ctw, cqw); + cMw.buildFrom(ctw, cqw); odo_vel.resize(6, false); odo_vel[0] = static_cast(pose_data.velocity.x); @@ -129,7 +129,7 @@ int main() vpQuaternionVector cqw(static_cast(pose_data.rotation.x), static_cast(pose_data.rotation.y), static_cast(pose_data.rotation.z), static_cast(pose_data.rotation.w)); - cMw.build(ctw, cqw); + cMw.buildFrom(ctw, cqw); odo_vel.resize(6, false); odo_vel[0] = static_cast(pose_data.velocity.x); diff --git a/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp b/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp index 5bf0cfbb8e..eca0f50f93 100644 --- a/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp +++ b/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp @@ -182,7 +182,7 @@ void vpMbDepthDenseTracker::computeVVS() if (computeCovariance) { L_true = m_L_depthDense; if (!isoJoIdentity) { - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); LVJ_true = (m_L_depthDense * cVo * oJo); } } @@ -194,7 +194,7 @@ void vpMbDepthDenseTracker::computeVVS() // cannot be estimated. This is particularly useful when considering // circles (rank 5) and cylinders (rank 4) if (isoJoIdentity) { - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); vpMatrix K; // kernel unsigned int rank = (m_L_depthDense * cVo).kernel(K); diff --git a/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp b/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp index 0f50af016a..24fba54627 100644 --- a/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp +++ b/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp @@ -187,7 +187,7 @@ void vpMbDepthNormalTracker::computeVVS() if (computeCovariance) { L_true = m_L_depthNormal; if (!isoJoIdentity) { - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); LVJ_true = (m_L_depthNormal * (cVo * oJo)); } } @@ -199,7 +199,7 @@ void vpMbDepthNormalTracker::computeVVS() // cannot be estimated. This is particularly useful when considering // circles (rank 5) and cylinders (rank 4) if (isoJoIdentity) { - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); vpMatrix K; // kernel unsigned int rank = (m_L_depthNormal * cVo).kernel(K); diff --git a/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp b/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp index 039d1039bc..412de6bee0 100644 --- a/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp +++ b/modules/tracker/mbt/src/edge/vpMbEdgeTracker.cpp @@ -231,7 +231,7 @@ void vpMbEdgeTracker::computeVVS(const vpImage &_I, unsigned int if (computeCovariance) { L_true = m_L_edge; if (!isoJoIdentity) { - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); LVJ_true = (m_L_edge * cVo * oJo); } } @@ -687,7 +687,7 @@ void vpMbEdgeTracker::computeVVSFirstPhasePoseEstimation(unsigned int iter, bool // estimated This is particularly useful when considering circles (rank 5) and // cylinders (rank 4) if (isoJoIdentity) { - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); vpMatrix K; // kernel unsigned int rank = (m_L_edge * cVo).kernel(K); @@ -713,7 +713,7 @@ void vpMbEdgeTracker::computeVVSFirstPhasePoseEstimation(unsigned int iter, bool v = -0.7 * LTL.pseudoInverse(LTL.getRows() * std::numeric_limits::epsilon()) * LTR; } else { - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); vpMatrix LVJ = (m_L_edge * cVo * oJo); vpMatrix LVJTLVJ = (LVJ).AtA(); vpColVector LVJTR; diff --git a/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp b/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp index c17bf847aa..a90d858afa 100644 --- a/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp +++ b/modules/tracker/mbt/src/hybrid/vpMbEdgeKltTracker.cpp @@ -837,7 +837,7 @@ void vpMbEdgeKltTracker::computeVVS(const vpImage &I, const unsig L_true = L; if (!isoJoIdentity) { vpVelocityTwistMatrix cVo; - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); LVJ_true = (L * cVo * oJo); } } diff --git a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp index 5187dde08c..92b0bc55e9 100644 --- a/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp +++ b/modules/tracker/mbt/src/klt/vpMbKltTracker.cpp @@ -824,7 +824,7 @@ void vpMbKltTracker::computeVVS() L_true = m_L_klt; if (!isoJoIdentity) { vpVelocityTwistMatrix cVo; - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); LVJ_true = (m_L_klt * cVo * oJo); } } diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp index b611bfc99c..ef241eaf67 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltCylinder.cpp @@ -416,7 +416,7 @@ void vpMbtDistanceKltCylinder::updateMask( corners.push_back(vpImagePoint((double)(solution[i][j].Y), (double)(solution[i][j].X))); } - polygon_area.build(corners); + polygon_area.buildFrom(corners); if (polygon_area.getArea() > max_area) { max_area = polygon_area.getArea(); index_max = i; diff --git a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp index 14db544add..4d01a2dee6 100644 --- a/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp +++ b/modules/tracker/mbt/src/klt/vpMbtDistanceKltPoints.cpp @@ -390,7 +390,7 @@ void vpMbtDistanceKltPoints::updateMask( corners.push_back(vpImagePoint((double)(solution[i][j].Y), (double)(solution[i][j].X))); } - polygon_area.build(corners); + polygon_area.buildFrom(corners); if (polygon_area.getArea() > max_area) { max_area = polygon_area.getArea(); index_max = i; diff --git a/modules/tracker/mbt/src/vpMbGenericTracker.cpp b/modules/tracker/mbt/src/vpMbGenericTracker.cpp index 760296c065..ac28776a57 100644 --- a/modules/tracker/mbt/src/vpMbGenericTracker.cpp +++ b/modules/tracker/mbt/src/vpMbGenericTracker.cpp @@ -321,7 +321,7 @@ void vpMbGenericTracker::computeVVS(std::map::const_iterator it = m_mapOfCameraTransformationMatrix.begin(); it != m_mapOfCameraTransformationMatrix.end(); ++it) { vpVelocityTwistMatrix cVo; - cVo.build(it->second); + cVo.buildFrom(it->second); mapOfVelocityTwist[it->first] = cVo; } @@ -364,7 +364,7 @@ void vpMbGenericTracker::computeVVS(std::map L_true = m_L; if (!isoJoIdentity) { vpVelocityTwistMatrix cVo; - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); LVJ_true = (m_L * cVo * oJo); } } @@ -6055,7 +6055,7 @@ void vpMbGenericTracker::TrackerWrapper::computeVVS(const vpImage // cannot be estimated. This is particularly useful when considering // circles (rank 5) and cylinders (rank 4) if (isoJoIdentity) { - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); vpMatrix K; // kernel unsigned int rank = (m_L * cVo).kernel(K); diff --git a/modules/tracker/mbt/src/vpMbTracker.cpp b/modules/tracker/mbt/src/vpMbTracker.cpp index 715cc3f17c..bd173a948a 100644 --- a/modules/tracker/mbt/src/vpMbTracker.cpp +++ b/modules/tracker/mbt/src/vpMbTracker.cpp @@ -284,7 +284,7 @@ void vpMbTracker::initClick(const vpImage *const I, const vpImage } finitpos.close(); - last_cMo.build(init_pos); + last_cMo.buildFrom(init_pos); std::cout << "Tracker initial pose read from " << ss.str() << ": " << std::endl << last_cMo << std::endl; @@ -1116,7 +1116,7 @@ void vpMbTracker::initFromPose(const vpImage *const I, const vpIm finit >> init_pos[i]; } - m_cMo.build(init_pos); + m_cMo.buildFrom(init_pos); if (I) { init(*I); @@ -1234,7 +1234,7 @@ void vpMbTracker::savePose(const std::string &filename) const std::fstream finitpos; finitpos.open(filename.c_str(), std::ios::out); - init_pos.build(m_cMo); + init_pos.buildFrom(m_cMo); finitpos << init_pos; finitpos.close(); } @@ -1801,7 +1801,7 @@ void vpMbTracker::loadCAOModel(const std::string &modelFile, std::vector::const_iterator it = vectorOfModelFilename.begin(); @@ -2963,7 +2963,7 @@ void vpMbTracker::computeVVSPoseEstimation(const bool isoJoIdentity, unsigned in } else { vpVelocityTwistMatrix cVo; - cVo.build(m_cMo); + cVo.buildFrom(m_cMo); vpMatrix LVJ = (L * (cVo * oJo)); vpMatrix LVJTLVJ = (LVJ).AtA(); vpColVector LVJTR; diff --git a/modules/tracker/mbt/test/generic-with-dataset/catchMbtJsonSettings.cpp b/modules/tracker/mbt/test/generic-with-dataset/catchMbtJsonSettings.cpp index 8c9f2a6d1b..36a20ceb43 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/catchMbtJsonSettings.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/catchMbtJsonSettings.cpp @@ -245,7 +245,7 @@ SCENARIO("MBT JSON Serialization", "[json]") t2.getClipping(newFlags); for (const auto &it : oldFlags) { unsigned int o = it.second; - unsigned int n; + unsigned int n = 0; REQUIRE_NOTHROW(n = newFlags[it.first]); THEN("Clipping flags for camera " + it.first + " should be the same") { diff --git a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp index b64199aca5..de84aeec61 100644 --- a/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp +++ b/modules/tracker/mbt/test/generic-with-dataset/testGenericTracker.cpp @@ -371,7 +371,7 @@ bool run(const std::string &input_directory, bool opt_click_allowed, bool opt_di map_thresh[vpMbGenericTracker::KLT_TRACKER] = useScanline ? std::pair(0.007, 1.9) : std::pair(0.007, 1.8); map_thresh[vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER] = - useScanline ? std::pair(0.005, 3.7) : std::pair(0.006, 3.4); + useScanline ? std::pair(0.005, 3.7) : std::pair(0.007, 3.4); #endif map_thresh[vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::DEPTH_DENSE_TRACKER] = useScanline ? std::pair(0.003, 1.7) : std::pair(0.002, 0.8); diff --git a/modules/vision/include/visp3/vision/vpHomography.h b/modules/vision/include/visp3/vision/vpHomography.h index e18120f2ee..94f1b52fd9 100644 --- a/modules/vision/include/visp3/vision/vpHomography.h +++ b/modules/vision/include/visp3/vision/vpHomography.h @@ -190,24 +190,14 @@ class VISP_EXPORT vpHomography : public vpArray2D //! Construction from translation and rotation and a plane. vpHomography(const vpPoseVector &arb, const vpPlane &bP); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -//! Construction from translation and rotation and a plane - void buildFrom(const vpRotationMatrix &aRb, const vpTranslationVector &atb, const vpPlane &bP); //! Construction from translation and rotation and a plane - void buildFrom(const vpThetaUVector &tu, const vpTranslationVector &atb, const vpPlane &bP); - //! Construction from translation and rotation and a plane - void buildFrom(const vpPoseVector &arb, const vpPlane &bP); - //! Construction from homogeneous matrix and a plane - void buildFrom(const vpHomogeneousMatrix &aMb, const vpPlane &bP); -#endif -//! Construction from translation and rotation and a plane - vpHomography &build(const vpRotationMatrix &aRb, const vpTranslationVector &atb, const vpPlane &bP); + vpHomography &buildFrom(const vpRotationMatrix &aRb, const vpTranslationVector &atb, const vpPlane &bP); //! Construction from translation and rotation and a plane - vpHomography &build(const vpThetaUVector &tu, const vpTranslationVector &atb, const vpPlane &bP); + vpHomography &buildFrom(const vpThetaUVector &tu, const vpTranslationVector &atb, const vpPlane &bP); //! Construction from translation and rotation and a plane - vpHomography &build(const vpPoseVector &arb, const vpPlane &bP); + vpHomography &buildFrom(const vpPoseVector &arb, const vpPlane &bP); //! Construction from homogeneous matrix and a plane - vpHomography &build(const vpHomogeneousMatrix &aMb, const vpPlane &bP); + vpHomography &buildFrom(const vpHomogeneousMatrix &aMb, const vpPlane &bP); /*! * Transform an homography from pixel space to calibrated domain. diff --git a/modules/vision/src/homography-estimation/vpHomography.cpp b/modules/vision/src/homography-estimation/vpHomography.cpp index 2e9de1c506..ce178ae71b 100644 --- a/modules/vision/src/homography-estimation/vpHomography.cpp +++ b/modules/vision/src/homography-estimation/vpHomography.cpp @@ -56,61 +56,27 @@ vpHomography::vpHomography(const vpHomography &H) : vpArray2D(3, 3), m_a vpHomography::vpHomography(const vpHomogeneousMatrix &aMb, const vpPlane &bP) : vpArray2D(3, 3), m_aMb(), m_bP() { - build(aMb, bP); + buildFrom(aMb, bP); } vpHomography::vpHomography(const vpThetaUVector &tu, const vpTranslationVector &atb, const vpPlane &p) : vpArray2D(3, 3), m_aMb(), m_bP() { - build(tu, atb, p); + buildFrom(tu, atb, p); } vpHomography::vpHomography(const vpRotationMatrix &aRb, const vpTranslationVector &atb, const vpPlane &p) : vpArray2D(3, 3), m_aMb(), m_bP() { - build(aRb, atb, p); + buildFrom(aRb, atb, p); } vpHomography::vpHomography(const vpPoseVector &arb, const vpPlane &p) : vpArray2D(3, 3), m_aMb(), m_bP() { - build(arb, p); + buildFrom(arb, p); } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -/** - * \deprecated You should use build(const vpHomogeneousMatrix &, const vpPlane &) instead. - */ -void vpHomography::buildFrom(const vpHomogeneousMatrix &aMb, const vpPlane &bP) -{ - build(aMb, bP); -} - -/** - * \deprecated You should use build(const vpThetaUVector &, const vpTranslationVector &, const vpPlane &) instead. - */ -void vpHomography::buildFrom(const vpThetaUVector &tu, const vpTranslationVector &atb, const vpPlane &p) -{ - build(tu, atb, p); -} - -/** - * \deprecated You should use build(const vpRotationMatrix &, const vpTranslationVector &, const vpPlane &) instead. - */ -void vpHomography::buildFrom(const vpRotationMatrix &aRb, const vpTranslationVector &atb, const vpPlane &p) -{ - build(aRb, atb, p); -} - -/** - * \deprecated You should use build(const vpPoseVector &, const vpPlane &) instead. - */ -void vpHomography::buildFrom(const vpPoseVector &arb, const vpPlane &p) -{ - build(arb, p); -} -#endif - -vpHomography &vpHomography::build(const vpHomogeneousMatrix &aMb, const vpPlane &bP) +vpHomography &vpHomography::buildFrom(const vpHomogeneousMatrix &aMb, const vpPlane &bP) { insert(aMb); insert(bP); @@ -118,7 +84,7 @@ vpHomography &vpHomography::build(const vpHomogeneousMatrix &aMb, const vpPlane return *this; } -vpHomography &vpHomography::build(const vpThetaUVector &tu, const vpTranslationVector &atb, const vpPlane &p) +vpHomography &vpHomography::buildFrom(const vpThetaUVector &tu, const vpTranslationVector &atb, const vpPlane &p) { insert(tu); insert(atb); @@ -127,7 +93,7 @@ vpHomography &vpHomography::build(const vpThetaUVector &tu, const vpTranslationV return *this; } -vpHomography &vpHomography::build(const vpRotationMatrix &aRb, const vpTranslationVector &atb, const vpPlane &p) +vpHomography &vpHomography::buildFrom(const vpRotationMatrix &aRb, const vpTranslationVector &atb, const vpPlane &p) { insert(aRb); insert(atb); @@ -136,10 +102,10 @@ vpHomography &vpHomography::build(const vpRotationMatrix &aRb, const vpTranslati return *this; } -vpHomography &vpHomography::build(const vpPoseVector &arb, const vpPlane &p) +vpHomography &vpHomography::buildFrom(const vpPoseVector &arb, const vpPlane &p) { double tx = arb[0], ty = arb[1], tz = arb[2], tux = arb[3], tuy = arb[4], tuz = arb[5]; - m_aMb.build(tx, ty, tz, tux, tuy, tuz); + m_aMb.buildFrom(tx, ty, tz, tux, tuy, tuz); insert(p); build(); return *this; diff --git a/modules/vision/src/pose-estimation/vpPoseLowe.cpp b/modules/vision/src/pose-estimation/vpPoseLowe.cpp index f9c59bc110..ec06bfb051 100644 --- a/modules/vision/src/pose-estimation/vpPoseLowe.cpp +++ b/modules/vision/src/pose-estimation/vpPoseLowe.cpp @@ -166,7 +166,7 @@ void fcn(int m, int n, double *xc, double *fvecc, double *jac, int ldfjac, int i u[index_1] = xc[index_4]; u[index_2] = xc[index_5]; - rd.build(u[index_0], u[index_1], u[index_2]); + rd.buildFrom(u[index_0], u[index_1], u[index_2]); /* a partir de l'axe de rotation, calcul de la matrice de rotation. */ // --comment: rot_mat of u rd diff --git a/modules/vision/test/homography/testDisplacement.cpp b/modules/vision/test/homography/testDisplacement.cpp index c09fdf1896..da69844c30 100644 --- a/modules/vision/test/homography/testDisplacement.cpp +++ b/modules/vision/test/homography/testDisplacement.cpp @@ -178,7 +178,7 @@ int main() std::cout << "n" << std::endl << n.t() << std::endl; vpPlane p1(n[0], n[1], n[2], 1.0); - H.build(R, T, p1); + H.buildFrom(R, T, p1); std::cout << "H" << std::endl << H << std::endl; } std::cout << "All tests succeed" << std::endl; diff --git a/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp b/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp index 81906d3a2f..778e60eef0 100644 --- a/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp +++ b/modules/vision/test/keypoint-with-dataset/testKeyPoint-2.cpp @@ -275,7 +275,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis vpImageIo::read(I, filenameRef); // Init pose at image 150 - cMo.build(0.02651282185, -0.03713587374, 0.6873765919, 2.314744454, 0.3492296488, -0.1226054828); + cMo.buildFrom(0.02651282185, -0.03713587374, 0.6873765919, 2.314744454, 0.3492296488, -0.1226054828); tracker.initFromPose(I, cMo); // Detect keypoints on the image 150 @@ -298,7 +298,7 @@ void run_test(const std::string &env_ipath, bool opt_click_allowed, bool opt_dis vpImageIo::read(I, filenameRef); // Init pose at image 200 - cMo.build(0.02965448956, -0.07283091786, 0.7253526051, 2.300529617, -0.4286674806, 0.1788761025); + cMo.buildFrom(0.02965448956, -0.07283091786, 0.7253526051, 2.300529617, -0.4286674806, 0.1788761025); tracker.initFromPose(I, cMo); // Detect keypoints on the image 200 diff --git a/modules/vision/test/pose/testPoseFeatures.cpp b/modules/vision/test/pose/testPoseFeatures.cpp index 7502c94974..9e30f0e6df 100644 --- a/modules/vision/test/pose/testPoseFeatures.cpp +++ b/modules/vision/test/pose/testPoseFeatures.cpp @@ -184,7 +184,7 @@ int test_pose(bool use_robust) else std::cout << "\nRobust estimated pose from visual features : " << std::endl; - pose_est.build(cMo_est); + pose_est.buildFrom(cMo_est); std::cout << pose_est.t() << std::endl; std::cout << "\nResulting covariance (Diag): " << std::endl; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h b/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h index 5bcf22027e..cb5742d7e3 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureDepth.h @@ -101,7 +101,7 @@ BEGIN_VISP_NAMESPACE * double Z; // You have to compute the value of Z. * double Zs; // You have to define the desired depth Zs. * //Set the point feature thanks to the current parameters. - * s.build(x, y, Z, log(Z/Zs)); + * s.buildFrom(x, y, Z, log(Z/Zs)); * * // Set eye-in-hand control law. * // The computed velocities will be expressed in the camera frame @@ -117,7 +117,7 @@ BEGIN_VISP_NAMESPACE * // The new parameters x, y and Z must be computed here. * * // Update the current point visual feature - * s.build(x, y, Z, log(Z/Zs)); + * s.buildFrom(x, y, Z, log(Z/Zs)); * * // compute the control law * vpColVector v = task.computeControlLaw(); // camera velocity @@ -149,7 +149,7 @@ BEGIN_VISP_NAMESPACE * double Z; // You have to compute the value of Z. * double Zs; // You have to define the desired depth Zs. * //Set the point feature thanks to the current parameters. - * s.build(x, y, Z, log(Z/Zs)); + * s.buildFrom(x, y, Z, log(Z/Zs)); * * // Compute the interaction matrix L_s for the current point feature * vpMatrix L = s.interaction(); @@ -181,11 +181,7 @@ class VISP_EXPORT vpFeatureDepth : public vpBasicFeature /* section Set coordinates */ - -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - void buildFrom(double x, double y, double Z, double LogZoverZstar); -#endif - vpFeatureDepth &build(const double &x, const double &y, const double &Z, const double &LogZoverZstar); + vpFeatureDepth &buildFrom(const double &x, const double &y, const double &Z, const double &LogZoverZstar); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h b/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h index 680255b6c0..0592229583 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h @@ -73,12 +73,8 @@ class VISP_EXPORT vpFeatureEllipse : public vpBasicFeature //! basic constructor vpFeatureEllipse(double x, double y, double n20, double n11, double n02); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - void buildFrom(double x, double y, double n20, double n11, double n02); - void buildFrom(double x, double y, double n20, double n11, double n02, double A, double B, double C); -#endif - vpFeatureEllipse &build(const double &x, const double &y, const double &n20, const double &n11, const double &n02); - vpFeatureEllipse &build(const double &x, const double &y, const double &n20, const double &n11, const double &n02, const double &A, const double &B, const double &C); + vpFeatureEllipse &buildFrom(const double &x, const double &y, const double &n20, const double &n11, const double &n02); + vpFeatureEllipse &buildFrom(const double &x, const double &y, const double &n20, const double &n11, const double &n02, const double &A, const double &B, const double &C); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h b/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h index 12ff2ad97f..9a018ab98a 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureLine.h @@ -116,14 +116,14 @@ BEGIN_VISP_NAMESPACE * double Cd = 1; * double Dd = -1; * // Set the line feature thanks to the desired parameters. - * sd.build(rhod, thetad, Ad,Bd, Cd, Dd); + * sd.buildFrom(rhod, thetad, Ad,Bd, Cd, Dd); * * vpFeatureLine s; //The current line feature. * // Sets the current features rho and theta * double rho; // You have to compute the value of rho. * double theta; // You have to compute the value of theta. * // Set the line feature thanks to the current parameters. - * s.build(rho, theta); + * s.buildFrom(rho, theta); * // In this case the parameters A, B, C, D are not needed because the interaction matrix is computed * // with the desired visual feature. * @@ -141,7 +141,7 @@ BEGIN_VISP_NAMESPACE * // The new parameters rho and theta must be computed here. * * // Update the current line visual feature - * s.build(rho, theta); + * s.buildFrom(rho, theta); * * // Compute the control law * vpColVector v = task.computeControlLaw(); // camera velocity @@ -172,7 +172,7 @@ BEGIN_VISP_NAMESPACE * // Sets the parameters which describe the equation of a plane in the camera frame : AX+BY+CZ+D=0. * double Ad = 0; double Bd = 0; double Cd = 1; double Dd = -1; * // Set the line feature thanks to the desired parameters. - * sd.build(rhod, thetad, Ad,Bd, Cd, Dd); + * sd.buildFrom(rhod, thetad, Ad,Bd, Cd, Dd); * * vpFeatureLine s; // The current line feature. * // Sets the current features rho and theta @@ -184,7 +184,7 @@ BEGIN_VISP_NAMESPACE * double C; // You have to compute the value of C. * double D; // You have to compute the value of D. D must not be equal to zero ! * // Set the line feature thanks to the current parameters. - * s.build(rho, theta, A, B, C, D); + * s.buildFrom(rho, theta, A, B, C, D); * * // Compute the interaction matrix L_s for the current line feature * vpMatrix L = s.interaction(); @@ -210,12 +210,8 @@ class VISP_EXPORT vpFeatureLine : public vpBasicFeature public: vpFeatureLine(); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - void buildFrom(double rho, double theta); - void buildFrom(double rho, double theta, double A, double B, double C, double D); -#endif - vpFeatureLine &build(const double &rho, const double &theta); - vpFeatureLine &build(const double &rho, const double &theta, const double &A, const double &B, const double &C, const double &D); + vpFeatureLine &buildFrom(const double &rho, const double &theta); + vpFeatureLine &buildFrom(const double &rho, const double &theta, const double &A, const double &B, const double &C, const double &D); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h index 86953e093d..02eea177b6 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h @@ -96,10 +96,7 @@ class VISP_EXPORT vpFeatureLuminance : public vpBasicFeature //! Destructor. virtual ~vpFeatureLuminance() VP_OVERRIDE; -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - void buildFrom(vpImage &I); -#endif - vpFeatureLuminance &build(vpImage &I); + vpFeatureLuminance &buildFrom(vpImage &I); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminanceMapping.h b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminanceMapping.h index 8b710512c8..95de2a2c5f 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminanceMapping.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminanceMapping.h @@ -352,7 +352,7 @@ class VISP_EXPORT vpLuminanceDCT : public vpLuminanceMapping */ vpLuminanceDCT(const vpLuminanceDCT &other); - vpLuminanceDCT &operator=(const vpLuminanceDCT &other) = default; + vpLuminanceDCT &operator=(const vpLuminanceDCT &) = default; void map(const vpImage &I, vpColVector &s) VP_OVERRIDE; void inverse(const vpColVector &s, vpImage &I) VP_OVERRIDE; @@ -363,7 +363,7 @@ class VISP_EXPORT vpLuminanceDCT : public vpLuminanceMapping void computeDCTMatrices(unsigned int rows, unsigned int cols); protected: - unsigned m_Ih, m_Iw; //! image dimensions (without borders) + unsigned int m_Ih, m_Iw; //! image dimensions (without borders) vpMatrix m_Imat; //! Image as a matrix vpMatrix m_dct; //! DCT representation of the image vpMatrix m_Dcols, m_Drows; //! the computed DCT matrices. The separable property of DCt is used so that a 1D DCT is computed on rows and another on columns of the result of the first dct; @@ -399,7 +399,7 @@ class VISP_EXPORT vpFeatureLuminanceMapping : public vpBasicFeature virtual ~vpFeatureLuminanceMapping() = default; - void build(vpImage &I); + void buildFrom(vpImage &I); void display(const vpCameraParameters &, const vpImage &, const vpColor & = vpColor::green, unsigned int = 1) const VP_OVERRIDE diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h index ce584938f2..e63a0d4900 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h @@ -102,7 +102,7 @@ BEGIN_VISP_NAMESPACE * // Set the depth of the point in the camera frame. * double Zd = 1; * // Set the point feature thanks to the desired parameters. - * sd.build(xd, yd, Zd); + * sd.buildFrom(xd, yd, Zd); * * vpFeaturePoint s; //The current point feature. * // Set the current features x and y @@ -110,7 +110,7 @@ BEGIN_VISP_NAMESPACE * double y; // You have to compute the value of y. * double Z; // You have to compute the value of Z. * // Set the point feature thanks to the current parameters. - * s.build(x, y, Z); + * s.buildFrom(x, y, Z); * // In this case the parameter Z is not necessary because the interaction matrix is computed * // with the desired visual feature. * @@ -128,7 +128,7 @@ BEGIN_VISP_NAMESPACE * // The new parameters x and y must be computed here. * * // Update the current point visual feature - * s.build(x, y, Z); + * s.buildFrom(x, y, Z); * * // Compute the control law * vpColVector v = task.computeControlLaw(); // camera velocity @@ -159,7 +159,7 @@ BEGIN_VISP_NAMESPACE * // Set the depth of the point in the camera frame. * double Zd = 1; * // Set the point feature thanks to the desired parameters. - * sd.build(xd, yd, Zd); + * sd.buildFrom(xd, yd, Zd); * * vpFeaturePoint s; //The current point feature. * // Set the current features x and y @@ -167,7 +167,7 @@ BEGIN_VISP_NAMESPACE * double y; // You have to compute the value of y. * double Z; // You have to compute the value of Z. * // Set the point feature thanks to the current parameters. - * s.build(x, y, Z); + * s.buildFrom(x, y, Z); * * // Compute the interaction matrix L_s for the current point feature * vpMatrix L = s.interaction(); @@ -191,10 +191,7 @@ class VISP_EXPORT vpFeaturePoint : public vpBasicFeature public: vpFeaturePoint(); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - void buildFrom(double x, double y, double Z); -#endif - vpFeaturePoint &build(const double &x, const double &y, const double &Z); + vpFeaturePoint &buildFrom(const double &x, const double &y, const double &Z); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h index 3d1cf14792..4b148a8cbe 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint3D.h @@ -110,19 +110,19 @@ BEGIN_VISP_NAMESPACE * vpPoint point(0.1, -0.1, 0); * * vpHomogeneousMatrix cMo; // Pose between the camera and the object frame - * cMo.build(0, 0, 1.2, 0, 0, 0); + * cMo.buildFrom(0, 0, 1.2, 0, 0, 0); * // ... cMo need here to be computed from a pose estimation * * point.changeFrame(cMo); // Compute the 3D point coordinates in the camera frame cP = cMo * oP * * // Creation of the current feature s * vpFeaturePoint3D s; - * s.build(point); // Initialize the feature from the 3D point coordinates in the camera frame: s=(X,Y,Z) + * s.buildFrom(point); // Initialize the feature from the 3D point coordinates in the camera frame: s=(X,Y,Z) * s.print(); * * // Creation of the desired feature s*. * vpFeaturePoint3D s_star; - * s_star.build(0, 0, 1); // Z*=1 meter + * s_star.buildFrom(0, 0, 1); // Z*=1 meter * s_star.print(); * * // Set eye-in-hand control law. @@ -143,7 +143,7 @@ BEGIN_VISP_NAMESPACE * point.changeFrame(cMo); // Compute the 3D point coordinates in the camera frame cP = cMo * oP * * // Update the current 3D point visual feature - * s.build(point); + * s.buildFrom(point); * * // compute the control law * vpColVector v = task.computeControlLaw(); // camera velocity @@ -182,19 +182,19 @@ BEGIN_VISP_NAMESPACE * vpPoint point(0.1, -0.1, 0); * * vpHomogeneousMatrix cMo; // Pose between the camera and the object frame - * cMo.build(0, 0, 1.2, 0, 0, 0); + * cMo.buildFrom(0, 0, 1.2, 0, 0, 0); * // ... cMo need here to be computed from a pose estimation * * point.changeFrame(cMo); // Compute the 3D point coordinates in the camera frame cP = cMo * oP * * // Creation of the current feature s * vpFeaturePoint3D s; - * s.build(point); // Initialize the feature from the 3D point coordinates in the camera frame + * s.buildFrom(point); // Initialize the feature from the 3D point coordinates in the camera frame * s.print(); * * // Creation of the desired feature s*. * vpFeaturePoint3D s_star; - * s_star.build(0, 0, 1); // Z*=1 meter + * s_star.buildFrom(0, 0, 1); // Z*=1 meter * s_star.print(); * * // Compute the L_s interaction matrix associated to the current feature @@ -218,16 +218,10 @@ class VISP_EXPORT vpFeaturePoint3D : public vpBasicFeature * Set coordinates */ -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS // build feature from a point (vpPoint) - void buildFrom(const vpPoint &p); + vpFeaturePoint3D &buildFrom(const vpPoint &p); // set the point XY and Z-coordinates - void buildFrom(double X, double Y, double Z); -#endif - // build feature from a point (vpPoint) - vpFeaturePoint3D &build(const vpPoint &p); - // set the point XY and Z-coordinates - vpFeaturePoint3D &build(const double &X, const double &Y, const double &Z); + vpFeaturePoint3D &buildFrom(const double &X, const double &Y, const double &Z); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h index b05e219d7f..74ade57a42 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h @@ -149,7 +149,7 @@ BEGIN_VISP_NAMESPACE * * // Initialize the desired pose between the camera and the object frame * vpHomogeneousMatrix cMod; - * cMod.build(0, 0, 1, 0, 0, 0); + * cMod.buildFrom(0, 0, 1, 0, 0, 0); * * // Compute the desired position of the point * for (int i = 0 ; i < 4 ; i++) { @@ -167,7 +167,7 @@ BEGIN_VISP_NAMESPACE * * // Initialize the current pose between the camera and the object frame * vpHomogeneousMatrix cMo; - * cMo.build(0, 0, 1.2, 0, 0, M_PI); + * cMo.buildFrom(0, 0, 1.2, 0, 0, M_PI); * // ... cMo need here to be computed from a pose estimation * * for (int i = 0 ; i < 4 ; i++) { @@ -241,12 +241,12 @@ BEGIN_VISP_NAMESPACE * // Creation of the current feature s * vpFeaturePointPolar s; * // Initialize the current feature - * s.build(0.1, M_PI, 1); // rho=0.1m, theta=pi, Z=1m + * s.buildFrom(0.1, M_PI, 1); // rho=0.1m, theta=pi, Z=1m * * // Creation of the desired feature s * vpFeaturePointPolar s_star; * // Initialize the desired feature - * s.build(0.15, 0, 0.8); // rho=0.15m, theta=0, Z=0.8m + * s.buildFrom(0.15, 0, 0.8); // rho=0.15m, theta=0, Z=0.8m * * // Compute the interaction matrix L_s for the current feature * vpMatrix L = s.interaction(); @@ -269,10 +269,7 @@ class VISP_EXPORT vpFeaturePointPolar : public vpBasicFeature // basic constructor vpFeaturePointPolar(); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - void buildFrom(double rho, double theta, double Z); -#endif - vpFeaturePointPolar &build(const double &rho, const double &theta, const double &Z); + vpFeaturePointPolar &buildFrom(const double &rho, const double &theta, const double &Z); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h b/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h index 2713ae3a58..c6d183c3a3 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureSegment.h @@ -70,12 +70,8 @@ class VISP_EXPORT vpFeatureSegment : public vpBasicFeature // empty constructor VP_EXPLICIT vpFeatureSegment(bool normalized = false); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - // change values of the segment - void buildFrom(double x1, double y1, double Z1, double x2, double y2, double Z2); -#endif // change values of the segment - vpFeatureSegment &build(const double &x1, const double &y1, const double &Z1, const double &x2, const double &y2, const double &Z2); + vpFeatureSegment &buildFrom(const double &x1, const double &y1, const double &Z1, const double &x2, const double &y2, const double &Z2); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h b/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h index 408185d2f0..7ce5a92b82 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureThetaU.h @@ -155,7 +155,7 @@ BEGIN_VISP_NAMESPACE * // in angle/axis parametrization between the current camera frame * // and the desired camera frame * vpFeatureThetaU s(vpFeatureThetaU::cRcd); - * s.build(cMcd); // Initialization of the feature + * s.buildFrom(cMcd); // Initialization of the feature * * // Set eye-in-hand control law. * // The computed velocities will be expressed in the camera frame @@ -171,7 +171,7 @@ BEGIN_VISP_NAMESPACE * // ... cMcd need here to be initialized from for example a pose estimation. * * // Update the current ThetaU visual feature - * s.build(cMcd); + * s.buildFrom(cMcd); * * // compute the control law * vpColVector v = task.computeControlLaw(); // camera velocity @@ -211,7 +211,7 @@ BEGIN_VISP_NAMESPACE * * // Creation of the current feature s * vpFeatureThetaU s(vpFeatureThetaU::cdRc); - * s.build(cdMc); // Initialization of the feature + * s.buildFrom(cdMc); // Initialization of the feature * * // Creation of the desired feature s*. By default this feature is * // initialized to zero @@ -261,18 +261,11 @@ class VISP_EXPORT vpFeatureThetaU : public vpBasicFeature vpFeatureThetaU(vpRotationMatrix &R, vpFeatureThetaURotationRepresentationType r); vpFeatureThetaU(vpHomogeneousMatrix &M, vpFeatureThetaURotationRepresentationType r); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - void buildFrom(vpThetaUVector &tu); + vpFeatureThetaU &buildFrom(const vpThetaUVector &tu); // build from a rotation matrix - void buildFrom(const vpRotationMatrix &R); + vpFeatureThetaU &buildFrom(const vpRotationMatrix &R); // build from an homogeneous matrix - void buildFrom(const vpHomogeneousMatrix &M); -#endif - vpFeatureThetaU &build(const vpThetaUVector &tu); - // build from a rotation matrix - vpFeatureThetaU &build(const vpRotationMatrix &R); - // build from an homogeneous matrix - vpFeatureThetaU &build(const vpHomogeneousMatrix &M); + vpFeatureThetaU &buildFrom(const vpHomogeneousMatrix &M); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h b/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h index 5f5f769673..84eb60988c 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureTranslation.h @@ -144,7 +144,7 @@ BEGIN_VISP_NAMESPACE * * // Creation of the current visual feature s * vpFeatureTranslation s(vpFeatureTranslation::cdMc); - * s.build(cdMc); // Initialization of the current feature s=(tx,ty,tz) + * s.buildFrom(cdMc); // Initialization of the current feature s=(tx,ty,tz) * * // Set eye-in-hand control law. * // The computed velocities will be expressed in the camera frame @@ -163,7 +163,7 @@ BEGIN_VISP_NAMESPACE * // ... cdMc need here to be initialized from for example a pose estimation. * * // Update the current 3D translation visual feature - * s.build(cdMc); + * s.buildFrom(cdMc); * * // compute the control law * vpColVector v = task.computeControlLaw(); // camera velocity @@ -202,7 +202,7 @@ BEGIN_VISP_NAMESPACE * * // Creation of the current feature s * vpFeatureTranslation s(vpFeatureTranslation::cdMc); - * s.build(cdMc); // Initialization of the feature + * s.buildFrom(cdMc); // Initialization of the feature * * // Creation of the desired feature s*. By default this feature is * // initialized to zero @@ -244,14 +244,14 @@ BEGIN_VISP_NAMESPACE * * // Creation of the desired visual feature s* * vpFeatureTranslation s_star(vpFeatureTranslation::cMo); - * s_star.build(cdMo); // Initialization of the desired feature s*=(tx*,ty*,tz*) + * s_star.buildFrom(cdMo); // Initialization of the desired feature s*=(tx*,ty*,tz*) * * vpHomogeneousMatrix cMo; * // ... cMo need here to be computed. * * // Creation of the current visual feature s * vpFeatureTranslation s(vpFeatureTranslation::cMo); - * s.build(cMo); // Initialization of the current feature s=(tx,ty,tz) + * s.buildFrom(cMo); // Initialization of the current feature s=(tx,ty,tz) * * // Set eye-in-hand control law. * // The computed velocities will be expressed in the camera frame @@ -270,7 +270,7 @@ BEGIN_VISP_NAMESPACE * // ... cMo need here to be computed from for example a pose estimation. * * // Update the current 3D translation visual feature - * s.build(cMo); + * s.buildFrom(cMo); * * // compute the control law * vpColVector v = task.computeControlLaw(); // camera velocity @@ -309,14 +309,9 @@ class VISP_EXPORT vpFeatureTranslation : public vpBasicFeature // cdMc is the displacement that the camera has to realize vpFeatureTranslation(vpHomogeneousMatrix &f2Mf1, vpFeatureTranslationRepresentationType r); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS // build from an homogeneous matrix // cdMc is the displacement that the camera has to realize - void buildFrom(const vpHomogeneousMatrix &f2Mf1); -#endif - // build from an homogeneous matrix - // cdMc is the displacement that the camera has to realize - vpFeatureTranslation &build(const vpHomogeneousMatrix &f2Mf1); + vpFeatureTranslation &buildFrom(const vpHomogeneousMatrix &f2Mf1); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h b/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h index 62e4cb1b3c..c856f8bf73 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureVanishingPoint.h @@ -81,10 +81,7 @@ class VISP_EXPORT vpFeatureVanishingPoint : public vpBasicFeature public: vpFeatureVanishingPoint(); -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS - void buildFrom(double x, double y); -#endif - vpFeatureVanishingPoint &build(const double &x, const double &y); + vpFeatureVanishingPoint &buildFrom(const double &x, const double &y); void display(const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1) const VP_OVERRIDE; diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderEllipse.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderEllipse.cpp index e700601649..f7bfbd0684 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderEllipse.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderEllipse.cpp @@ -78,7 +78,7 @@ void vpFeatureBuilder::create(vpFeatureEllipse &s, const vpCircle &t) s.setABC(A, B, C); // 2D data - s.build(t.p[0], t.p[1], t.p[2], t.p[3], t.p[4]); + s.buildFrom(t.p[0], t.p[1], t.p[2], t.p[3], t.p[4]); } /*! @@ -112,7 +112,7 @@ void vpFeatureBuilder::create(vpFeatureEllipse &s, const vpSphere &t) s.setABC(A, B, C); // 2D data - s.build(t.p[0], t.p[1], t.p[2], t.p[3], t.p[4]); + s.buildFrom(t.p[0], t.p[1], t.p[2], t.p[3], t.p[4]); } #ifdef VISP_HAVE_MODULE_BLOB @@ -139,7 +139,7 @@ void vpFeatureBuilder::create(vpFeatureEllipse &s, const vpCameraParameters &cam vpPixelMeterConversion::convertPoint(cam, blob.getCog(), xc, yc); vpColVector nij = blob.get_nij(); - s.build(xc, yc, nij[0], nij[1], nij[2]); + s.buildFrom(xc, yc, nij[0], nij[1], nij[2]); } /*! @@ -165,7 +165,7 @@ void vpFeatureBuilder::create(vpFeatureEllipse &s, const vpCameraParameters &cam vpPixelMeterConversion::convertPoint(cam, blob.getCog(), xc, yc); vpColVector nij = blob.get_nij(); - s.build(xc, yc, nij[0], nij[1], nij[2]); + s.buildFrom(xc, yc, nij[0], nij[1], nij[2]); } #endif //#ifdef VISP_HAVE_MODULE_BLOB @@ -193,7 +193,7 @@ void vpFeatureBuilder::create(vpFeatureEllipse &s, const vpCameraParameters &cam vpPixelMeterConversion::convertEllipse(cam, ellipse.getCenter(), ellipse.get_nij()[0], ellipse.get_nij()[1], ellipse.get_nij()[2], xg, yg, n20, n11, n02); - s.build(xg, yg, n20, n11, n02); + s.buildFrom(xg, yg, n20, n11, n02); } #endif //#ifdef VISP_HAVE_MODULE_ME diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderLine.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderLine.cpp index 7000547b95..f1da84e748 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderLine.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderLine.cpp @@ -228,7 +228,7 @@ void vpFeatureBuilder::create(vpFeatureLine &s, const vpCameraParameters &cam, c theta += 2 * M_PI; } - s.build(rho, theta); + s.buildFrom(rho, theta); } catch (...) { vpERROR_TRACE("Error caught"); diff --git a/modules/visual_features/src/feature-builder/vpFeatureBuilderSegment.cpp b/modules/visual_features/src/feature-builder/vpFeatureBuilderSegment.cpp index c86272bef3..a27097e808 100644 --- a/modules/visual_features/src/feature-builder/vpFeatureBuilderSegment.cpp +++ b/modules/visual_features/src/feature-builder/vpFeatureBuilderSegment.cpp @@ -50,7 +50,7 @@ BEGIN_VISP_NAMESPACE * \param d1 : The dot corresponding to the first point of the segment. * \param d2 : The dot corresponding to the second point of the segment. */ -void vpFeatureBuilder::create(vpFeatureSegment &s, const vpCameraParameters &cam, const vpDot &d1, const vpDot &d2) + void vpFeatureBuilder::create(vpFeatureSegment &s, const vpCameraParameters &cam, const vpDot &d1, const vpDot &d2) { double x1 = 0, y1 = 0, x2 = 0, y2 = 0; @@ -161,6 +161,6 @@ void vpFeatureBuilder::create(vpFeatureSegment &s, vpPoint &P1, vpPoint &P2) double Z1 = P1.cP[2] / P1.cP[3]; double Z2 = P2.cP[2] / P2.cP[3]; - s.build(x1, y1, Z1, x2, y2, Z2); + s.buildFrom(x1, y1, Z1, x2, y2, Z2); } END_VISP_NAMESPACE diff --git a/modules/visual_features/src/visual-feature/vpFeatureDepth.cpp b/modules/visual_features/src/visual-feature/vpFeatureDepth.cpp index 3dce9b30bf..15250b2f6a 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureDepth.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureDepth.cpp @@ -201,7 +201,7 @@ void vpFeatureDepth::set_xyZLogZoverZstar(double x_, double y_, double Z_, doubl \code // Creation of the current feature s vpFeatureDepth s; - s.build(0, 0, 5, log(5/1)); // The current depth is 5 meters and the desired is 1 meter. + s.buildFrom(0, 0, 5, log(5/1)); // The current depth is 5 meters and the desired is 1 meter. vpMatrix L_x = s.interaction(); \endcode @@ -329,7 +329,7 @@ vpColVector vpFeatureDepth::error(const vpBasicFeature &s_star, unsigned int sel vpFeatureDepth s; // Current visual feature s // Creation of the current feature s - s.build(0, 0, 5, log(5/1)); + s.buildFrom(0, 0, 5, log(5/1)); s.print(); // print all the 2 components of the feature \endcode @@ -347,9 +347,7 @@ void vpFeatureDepth::print(unsigned int select) const } } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const double &, const double &, const double &, const double &) instead. Build a 3D depth visual feature from the point coordinates \f$ x \f$ and \f$ y \f$ given in the camera frame, \f$ Z \f$ which describes the depth and \f$ log(\frac{Z}{Z^*}) \f$ which represents the logarithm of the current depth @@ -360,24 +358,7 @@ void vpFeatureDepth::print(unsigned int select) const \param Z_ : The \f$ Z \f$ parameter. \param LogZoverZstar : The \f$ log(\frac{Z}{Z^*}) \f$ parameter. */ -void vpFeatureDepth::buildFrom(double x_, double y_, double Z_, double LogZoverZstar) -{ - build(x_, y_, Z_, LogZoverZstar); -} -#endif - -/*! - Build a 3D depth visual feature from the point coordinates \f$ x \f$ and \f$ - y \f$ given in the camera frame, \f$ Z \f$ which describes the depth and \f$ - log(\frac{Z}{Z^*}) \f$ which represents the logarithm of the current depth - relative to the desired depth. - - \param x_ : The \f$ x \f$ parameter. - \param y_ : The \f$ y \f$ parameter. - \param Z_ : The \f$ Z \f$ parameter. - \param LogZoverZstar : The \f$ log(\frac{Z}{Z^*}) \f$ parameter. -*/ -vpFeatureDepth &vpFeatureDepth::build(const double &x_, const double &y_, const double &Z_, const double &LogZoverZstar) +vpFeatureDepth &vpFeatureDepth::buildFrom(const double &x_, const double &y_, const double &Z_, const double &LogZoverZstar) { s[0] = LogZoverZstar; diff --git a/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp b/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp index 8930eacecd..860fcca22f 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp @@ -81,7 +81,7 @@ void vpFeatureEllipse::init() } vpFeatureEllipse::vpFeatureEllipse() : A(0), B(0), C(0) { init(); } -vpFeatureEllipse::vpFeatureEllipse(double x, double y, double n20, double n11, double n02) { this->build(x, y, n20, n11, n02); } +vpFeatureEllipse::vpFeatureEllipse(double x, double y, double n20, double n11, double n02) { this->buildFrom(x, y, n20, n11, n02); } //! compute the interaction matrix from a subset a the possible features @@ -280,25 +280,7 @@ void vpFeatureEllipse::print(unsigned int select) const std::cout << "A = " << A << " B = " << B << " C = " << C << std::endl; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -/*! - \deprecated You should use build(const double &, const double &, const double &, const double &, const double &) instead. - */ -void vpFeatureEllipse::buildFrom(double x, double y, double n20, double n11, double n02) -{ - build(x, y, n20, n11, n02); -} - -/*! - \deprecated You should use build(const double &, const double &, const double &, const double &, const double &) instead. - */ -void vpFeatureEllipse::buildFrom(double x, double y, double n20, double n11, double n02, double a, double b, double c) -{ - build(x, y, n20, n11, n02, a, b, c); -} -#endif - -vpFeatureEllipse &vpFeatureEllipse::build(const double &x, const double &y, const double &n20, const double &n11, const double &n02) +vpFeatureEllipse &vpFeatureEllipse::buildFrom(const double &x, const double &y, const double &n20, const double &n11, const double &n02) { s[0] = x; s[1] = y; @@ -312,7 +294,7 @@ vpFeatureEllipse &vpFeatureEllipse::build(const double &x, const double &y, cons return *this; } -vpFeatureEllipse &vpFeatureEllipse::build(const double &x, const double &y, const double &n20, const double &n11, const double &n02, const double &a, const double &b, const double &c) +vpFeatureEllipse &vpFeatureEllipse::buildFrom(const double &x, const double &y, const double &n20, const double &n11, const double &n02, const double &a, const double &b, const double &c) { s[0] = x; s[1] = y; diff --git a/modules/visual_features/src/visual-feature/vpFeatureLine.cpp b/modules/visual_features/src/visual-feature/vpFeatureLine.cpp index a86788be39..6833b928f4 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureLine.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureLine.cpp @@ -169,7 +169,7 @@ void vpFeatureLine::setABCD(double A_, double B_, double C_, double D_) \code // Creation of the current feature s vpFeatureLine s; - s.build(0, 0, 0, 0, 1, -1); + s.buildFrom(0, 0, 0, 0, 1, -1); vpMatrix L_theta = s.interaction( vpFeatureLine::selectTheta() ); \endcode @@ -180,7 +180,7 @@ void vpFeatureLine::setABCD(double A_, double B_, double C_, double D_) \code // Creation of the current feature s vpFeatureLine s; - s.build(0, 0, 0, 0, 1, -1); + s.buildFrom(0, 0, 0, 0, 1, -1); vpMatrix L_theta = s.interaction( vpBasicFeature::FEATURE_ALL ); \endcode @@ -292,11 +292,11 @@ vpMatrix vpFeatureLine::interaction(unsigned int select) \code // Creation of the current feature s vpFeatureLine s; - s.build(0, 0, 0, 0, 1, -1); + s.buildFrom(0, 0, 0, 0, 1, -1); // Creation of the desired feature s* vpFeatureLine s_star; - s_star.build(0, 0, 0, 0, 1, -5); + s_star.buildFrom(0, 0, 0, 0, 1, -5); // Compute the interaction matrix for the theta feature vpMatrix L_theta = s.interaction( vpFeatureLine::selectTheta() ); @@ -349,7 +349,7 @@ vpColVector vpFeatureLine::error(const vpBasicFeature &s_star, unsigned int sele vpFeatureLine s; // Current visual feature s // Creation of the current feature s - s.build(0, 0); + s.buildFrom(0, 0); s.print(); // print all the 2 components of the feature s.print(vpBasicFeature::FEATURE_ALL); // same behavior then previous line @@ -369,62 +369,6 @@ void vpFeatureLine::print(unsigned int select) const std::cout << std::endl; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -/*! - \deprecated You should use build(const double &, const double &) instead. - Build a 2D line visual feature from the line equation parameters \f$ - \rho \f$ and \f$ \theta \f$ given in the image plan. - - \f[ x \; cos(\theta) + y \; sin(\theta) -\rho = 0 \f] - - See the vpFeatureLine class description for more details about \f$ - \rho \f$ and \f$ \theta \f$. - - \param rho : The \f$ \rho \f$ parameter. - \param theta : The \f$ \theta \f$ parameter. - -*/ -void vpFeatureLine::buildFrom(double rho, double theta) -{ - s[0] = rho; - s[1] = theta; - for (int i = 0; i < 2; i++) - flags[i] = true; -} - -/*! - \deprecated You should use build(const double &, const double &, const double &, const double &, const double &, const double &) instead. - Build a 2D line visual feature from the line equation parameters \f$ - \rho \f$ and \f$ \theta \f$ given in the image plan. The - parameters A, B, C and D which describe the equation of a plan to - which the line belongs, are set in the same time. - - \f[ x \; cos(\theta) + y \; sin(\theta) -\rho = 0 \f] - \f[ AX + BY + CZ + D = 0 \f] - - See the vpFeatureLine class description for more details about \f$ - \rho \f$ and \f$ \theta \f$. - - The A, B, C, D parameters are needed to compute the interaction - matrix associated to a visual feature. Normally, two plans are - needed to describe a line (the intersection of those two plans). But - to compute the interaction matrix only one plan equation is - required. The only one restrictions is that the value of D must not - be equal to zero ! - - \param rho : The \f$ \rho \f$ parameter. - \param theta : The \f$ \theta \f$ parameter. - \param A_ : A parameter of the plan equation. - \param B_ : B parameter of the plan equation. - \param C_ : C parameter of the plan equation. - \param D_ : D parameter of the plan equation. - -*/ -void vpFeatureLine::buildFrom(double rho, double theta, double A_, double B_, double C_, double D_) -{ - build(rho, theta, A_, B_, C_, D_); -} -#endif /*! Build a 2D line visual feature from the line equation parameters \f$ @@ -439,7 +383,7 @@ void vpFeatureLine::buildFrom(double rho, double theta, double A_, double B_, do \param theta : The \f$ \theta \f$ parameter. */ -vpFeatureLine &vpFeatureLine::build(const double &rho, const double &theta) +vpFeatureLine &vpFeatureLine::buildFrom(const double &rho, const double &theta) { s[0] = rho; s[1] = theta; @@ -477,7 +421,7 @@ vpFeatureLine &vpFeatureLine::build(const double &rho, const double &theta) \param D_ : D parameter of the plan equation. */ -vpFeatureLine &vpFeatureLine::build(const double &rho, const double &theta, const double &A_, const double &B_, const double &C_, const double &D_) +vpFeatureLine &vpFeatureLine::buildFrom(const double &rho, const double &theta, const double &A_, const double &B_, const double &C_, const double &D_) { s[0] = rho; s[1] = theta; diff --git a/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp b/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp index 76d0ddd78e..62c35ddb38 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureLuminance.cpp @@ -173,24 +173,12 @@ unsigned int vpFeatureLuminance::getBorder() const { return bord; } void vpFeatureLuminance::setCameraParameters(const vpCameraParameters &_cam) { cam = _cam; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -/*! - \deprecated You should use build(vpImage &) instead. - Build a luminance feature directly from the image -*/ - -void vpFeatureLuminance::buildFrom(vpImage &I) -{ - build(I); -} -#endif - /*! Build a luminance feature directly from the image */ -vpFeatureLuminance &vpFeatureLuminance::build(vpImage &I) +vpFeatureLuminance &vpFeatureLuminance::buildFrom(vpImage &I) { unsigned int l = 0; double Ix, Iy; diff --git a/modules/visual_features/src/visual-feature/vpFeatureLuminanceMapping.cpp b/modules/visual_features/src/visual-feature/vpFeatureLuminanceMapping.cpp index a7ff48337e..68c6a93214 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureLuminanceMapping.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureLuminanceMapping.cpp @@ -552,9 +552,9 @@ vpFeatureLuminanceMapping *vpFeatureLuminanceMapping::duplicate() const return new vpFeatureLuminanceMapping(*this); } -void vpFeatureLuminanceMapping::build(vpImage &I) +void vpFeatureLuminanceMapping::buildFrom(vpImage &I) { - m_featI.build(I); + m_featI.buildFrom(I); m_featI.interaction(m_LI); m_mapping->map(I, s); } diff --git a/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp b/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp index dd8b3e0783..983016dfb8 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePoint.cpp @@ -195,7 +195,7 @@ void vpFeaturePoint::set_xyZ(double x_, double y_, double Z_) \code // Creation of the current feature s vpFeaturePoint s; - s.build(0, 0, 1); + s.buildFrom(0, 0, 1); vpMatrix L_x = s.interaction( vpFeaturePoint::selectX() ); \endcode @@ -205,7 +205,7 @@ void vpFeaturePoint::set_xyZ(double x_, double y_, double Z_) \code // Creation of the current feature s vpFeaturePoint s; - s.build(0, 0, 1); + s.buildFrom(0, 0, 1); vpMatrix L_x = s.interaction( vpBasicFeature::FEATURE_ALL ); \endcode @@ -311,11 +311,11 @@ vpMatrix vpFeaturePoint::interaction(unsigned int select) \code // Creation of the current feature s vpFeaturePoint s; - s.build(0, 0, 1); + s.buildFrom(0, 0, 1); // Creation of the desired feature s* vpFeaturePoint s_star; - s_star.build(1, 1, 1); + s_star.buildFrom(1, 1, 1); // Compute the interaction matrix for the x feature vpMatrix L_x = s.interaction( vpFeaturePoint::selectX() ); @@ -361,7 +361,7 @@ vpColVector vpFeaturePoint::error(const vpBasicFeature &s_star, unsigned int sel vpFeaturePoint s; // Current visual feature s // Creation of the current feature s - s.build(0, 0, 1); + s.buildFrom(0, 0, 1); s.print(); // print all the 2 components of the feature s.print(vpBasicFeature::FEATURE_ALL); // same behavior then previous line @@ -379,9 +379,7 @@ void vpFeaturePoint::print(unsigned int select) const std::cout << std::endl; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS /*! - \deprecated You should use build(const double &, const double &, const double &) instead. Build a 2D point visual feature from the point coordinates in the image plan \f$ x \f$ and \f$ y \f$. The parameter Z which describes the depth, is set in the same time. @@ -393,25 +391,7 @@ void vpFeaturePoint::print(unsigned int select) const \param y_ : The \f$ y \f$ parameter. \param Z_ : The \f$ Z \f$ parameter. */ -void vpFeaturePoint::buildFrom(double x_, double y_, double Z_) -{ - build(x_, y_, Z_); -} -#endif - -/*! - Build a 2D point visual feature from the point coordinates in the image plan - \f$ x \f$ and \f$ y \f$. The parameter Z which describes the depth, is set - in the same time. - - See the vpFeaturePoint class description for more details about \f$ x \f$ - and \f$ y \f$. - - \param x_ : The \f$ x \f$ parameter. - \param y_ : The \f$ y \f$ parameter. - \param Z_ : The \f$ Z \f$ parameter. -*/ -vpFeaturePoint &vpFeaturePoint::build(const double &x_, const double &y_, const double &Z_) +vpFeaturePoint &vpFeaturePoint::buildFrom(const double &x_, const double &y_, const double &Z_) { s[0] = x_; diff --git a/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp b/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp index 5514cc20d0..f71f9eb570 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePoint3D.cpp @@ -196,7 +196,7 @@ double vpFeaturePoint3D::get_Z() const { return s[2]; } ... // Creation of the current feature s vpFeaturePoint3D s; - s.build(point); + s.buildFrom(point); vpMatrix L_X = s.interaction( vpFeaturePoint3D::selectX() ); \endcode @@ -383,50 +383,6 @@ vpColVector vpFeaturePoint3D::error(const vpBasicFeature &s_star, unsigned int s return e; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -/*! - \deprecated You should use build(const vpPoint &) instead. - Build a 3D point visual feature from the camera frame coordinates - \f$(X,Y,Z)\f$ of a point. - - \param p : A point with camera frame coordinates \f${^c}P=(X,Y,Z)\f$ - up to date (see vpPoint class). - - \exception vpFeatureException::badInitializationError: If the depth - (\f$Z\f$ coordinate) is negative. That means that the 3D point is - behind the camera which is not possible. - - \exception vpFeatureException::badInitializationError: If the depth - (\f$Z\f$ coordinate) is null. That means that the 3D point is - on the camera which is not possible. -*/ -void vpFeaturePoint3D::buildFrom(const vpPoint &p) -{ - build(p); -} - -/*! - \deprecated You should use build(const double &, const double &, const double &) instead. - Build a 3D point visual feature from the camera frame coordinates - \f$(X,Y,Z)\f$ of a point. - - \param X,Y,Z : Camera frame coordinates \f$(X,Y,Z)\f$ of a 3D point. - - \exception vpFeatureException::badInitializationError: If the depth - (\f$Z\f$ coordinate) is negative. That means that the 3D point is - on the camera which is not possible. - - \exception vpFeatureException::badInitializationError: If the depth - (\f$Z\f$ coordinate) is null. That means that the 3D point is - on the camera which is not possible. - -*/ -void vpFeaturePoint3D::buildFrom(double X, double Y, double Z) -{ - build(X, Y, Z); -} -#endif - /*! Build a 3D point visual feature from the camera frame coordinates @@ -443,9 +399,8 @@ void vpFeaturePoint3D::buildFrom(double X, double Y, double Z) (\f$Z\f$ coordinate) is null. That means that the 3D point is on the camera which is not possible. */ -vpFeaturePoint3D &vpFeaturePoint3D::build(const vpPoint &p) +vpFeaturePoint3D &vpFeaturePoint3D::buildFrom(const vpPoint &p) { - // cP is expressed in homogeneous coordinates // we devide by the fourth coordinate s[0] = p.cP[0] / p.cP[3]; @@ -489,7 +444,7 @@ vpFeaturePoint3D &vpFeaturePoint3D::build(const vpPoint &p) on the camera which is not possible. */ -vpFeaturePoint3D &vpFeaturePoint3D::build(const double &X, const double &Y, const double &Z) +vpFeaturePoint3D &vpFeaturePoint3D::buildFrom(const double &X, const double &Y, const double &Z) { s[0] = X; s[1] = Y; @@ -531,7 +486,7 @@ vpFeaturePoint3D &vpFeaturePoint3D::build(const double &X, const double &Y, cons // Creation of the current feature s vpFeaturePoint3D s; - s.build(point); + s.buildFrom(point); s.print(); // print all the 3 components of the translation feature s.print(vpBasicFeature::FEATURE_ALL); // same behavior then previous line diff --git a/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp b/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp index 68535ea5cf..1d6c711a5d 100644 --- a/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp +++ b/modules/visual_features/src/visual-feature/vpFeaturePointPolar.cpp @@ -219,7 +219,7 @@ double vpFeaturePointPolar::get_Z() const { return this->Z; } double theta = M_PI; double Z = 1; // Creation of the current feature s - s.build(rho, theta, Z); + s.buildFrom(rho, theta, Z); // Build the interaction matrix L_s vpMatrix L = s.interaction(); \endcode @@ -368,13 +368,13 @@ vpMatrix vpFeaturePointPolar::interaction(unsigned int select) \code vpFeaturePointPolar s; // Creation of the current feature s - s.build(0.2, ..., 1); // rho and Z need to be set + s.buildFrom(0.2, ..., 1); // rho and Z need to be set // Build the interaction matrix L associated to rho component vpMatrix L_rho = s.interaction( vpFeaturePointPolar::selectRho() ); vpFeaturePointPolar s_star; // Creation of the desired feature s* - s_star.build(0.45, ..., 1.2); // rho and Z need to be set + s_star.buildFrom(0.45, ..., 1.2); // rho and Z need to be set // Compute the error vector (s-s*) for the rho feature vpColVector e = s.error(s_star, vpFeaturePointPolar::selectRho()); @@ -431,7 +431,7 @@ vpColVector vpFeaturePointPolar::error(const vpBasicFeature &s_star, unsigned in \code // Creation of the current feature s vpFeaturePointPolar s; - s.build(0.1, M_PI_2, 1.3); + s.buildFrom(0.1, M_PI_2, 1.3); s.print(); // print all the 2 components of the image point feature s.print(vpBasicFeature::FEATURE_ALL); // same behavior then previous line @@ -449,31 +449,7 @@ void vpFeaturePointPolar::print(unsigned int select) const std::cout << std::endl; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -/*! - \deprecated You should use build(const double &, const double &, const double &) instead. - Build a 2D image point visual feature with polar coordinates. - - \param rho, theta : Polar coordinates \f$(\rho,\theta)\f$ of - the image point. - - \param Z_ : 3D depth of the point in the camera frame. - - \exception vpFeatureException::badInitializationError: If the depth - (\f$Z\f$ coordinate) is negative. That means that the 3D point is - behind the camera which is not possible. - - \exception vpFeatureException::badInitializationError: If the depth - (\f$Z\f$ coordinate) is null. That means that the 3D point is - on the camera which is not possible. -*/ -void vpFeaturePointPolar::buildFrom(double rho, double theta, double Z_) -{ - build(rho, theta, Z_); -} -#endif - -vpFeaturePointPolar &vpFeaturePointPolar::build(const double &rho, const double &theta, const double &Z_) +vpFeaturePointPolar &vpFeaturePointPolar::buildFrom(const double &rho, const double &theta, const double &Z_) { s[0] = rho; diff --git a/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp b/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp index ae2d05db56..744b180998 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureSegment.cpp @@ -162,7 +162,7 @@ vpFeatureSegment::vpFeatureSegment(bool normalized) * * // Build the segment visual feature * vpFeatureSegment s; - * s.build(p1.get_x(), p1.get_y(), p1.get_Z(), p2.get_x(), p2.get_y(), p2.get_Z()); + * s.buildFrom(p1.get_x(), p1.get_y(), p1.get_Z(), p2.get_x(), p2.get_y(), p2.get_Z()); * * // Compute the interaction matrix * vpMatrix L = s.interaction( vpBasicFeature::FEATURE_ALL ); @@ -539,9 +539,7 @@ void vpFeatureSegment::display(const vpCameraParameters &cam, const vpImagef2Mf1 = f2Mf1_; s[0] = f2Mf1[0][3]; @@ -287,7 +270,7 @@ double vpFeatureTranslation::get_Tz() const { return s[2]; } ... // Creation of the current feature s vpFeatureTranslation s(vpFeatureTranslation::cdMc); - s.build(cdMc); + s.buildFrom(cdMc); vpMatrix L_x = s.interaction( vpFeatureTranslation::selectTx() ); \endcode @@ -570,7 +553,7 @@ vpColVector vpFeatureTranslation::error(const vpBasicFeature &s_star, unsigned i // Creation of the current feature s vpFeatureTranslation s(vpFeatureTranslation::cdMc); - s.build(cdMc); + s.buildFrom(cdMc); s.print(); // print all the 3 components of the translation feature s.print(vpBasicFeature::FEATURE_ALL); // same behavior then previous line diff --git a/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp b/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp index 0a2f18ce15..1b8c93152f 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureVanishingPoint.cpp @@ -59,7 +59,7 @@ BEGIN_VISP_NAMESPACE /*! * Vanishing point visual feature initialization. */ -void vpFeatureVanishingPoint::init() + void vpFeatureVanishingPoint::init() { // Feature dimension dim_s = 5; @@ -99,7 +99,7 @@ void vpFeatureVanishingPoint::set_y(double y) //! Get vanishing point feature \f$ y \f$ value. double vpFeatureVanishingPoint::get_y() const { return s[1]; } -//! Set vanishing point visual feature \f$ {\bf s} = (x, y) \f$ from cartesian coordinates. Same as build(). +//! Set vanishing point visual feature \f$ {\bf s} = (x, y) \f$ from cartesian coordinates. Same as buildFrom(). void vpFeatureVanishingPoint::set_xy(double x, double y) { set_x(x); @@ -346,16 +346,8 @@ void vpFeatureVanishingPoint::print(unsigned int select) const std::cout << std::endl; } -#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS -/** - * \deprecated You should use build(const double&, const double &) instead. - * \brief Set vanishing point visual feature \f$ {\bf s} = (x, y) \f$ from cartesian coordinates. Same as set_xy(). - */ -void vpFeatureVanishingPoint::buildFrom(double x, double y) { set_xy(x, y); } -#endif - //! Set vanishing point visual feature \f$ {\bf s} = (x, y) \f$ from cartesian coordinates. Same as set_xy(). -vpFeatureVanishingPoint &vpFeatureVanishingPoint::build(const double &x, const double &y) +vpFeatureVanishingPoint &vpFeatureVanishingPoint::buildFrom(const double &x, const double &y) { set_xy(x, y); return *this; diff --git a/modules/vs/include/visp3/vs/vpServo.h b/modules/vs/include/visp3/vs/vpServo.h index 6f81eaf97e..b8cfc55ace 100644 --- a/modules/vs/include/visp3/vs/vpServo.h +++ b/modules/vs/include/visp3/vs/vpServo.h @@ -98,8 +98,8 @@ BEGIN_VISP_NAMESPACE * vpFeatureTranslation s_t(vpFeatureTranslation::cdMc); * vpFeatureThetaU s_tu(vpFeatureThetaU::cdRc); * // Set the initial values of the current visual feature s = (c*_t_c, ThetaU) - * s_t.build(cdMc); - * s_tu.build(cdMc); + * s_t.buildFrom(cdMc); + * s_tu.buildFrom(cdMc); * * // Build the desired visual feature s* = (0,0) * vpFeatureTranslation s_star_t(vpFeatureTranslation::cdMc); // Default initialization to zero @@ -131,8 +131,8 @@ BEGIN_VISP_NAMESPACE * // ... cdMc is here the result of a pose estimation * * // Update the current visual feature s - * s_t.build(cdMc); // Update translation visual feature - * s_tu.build(cdMc); // Update ThetaU visual feature + * s_t.buildFrom(cdMc); // Update translation visual feature + * s_tu.buildFrom(cdMc); // Update ThetaU visual feature * * v = task.computeControlLaw(); // Compute camera velocity skew * error = ( task.getError() ).sumSquare(); // error = s^2 - s_star^2 @@ -1047,7 +1047,7 @@ class VISP_EXPORT vpServo */ void set_cVe(const vpHomogeneousMatrix &cMe) { - cVe.build(cMe); + cVe.buildFrom(cMe); init_cVe = true; } @@ -1069,7 +1069,7 @@ class VISP_EXPORT vpServo */ void set_cVf(const vpHomogeneousMatrix &cMf) { - cVf.build(cMf); + cVf.buildFrom(cMf); init_cVf = true; } @@ -1091,7 +1091,7 @@ class VISP_EXPORT vpServo */ void set_fVe(const vpHomogeneousMatrix &fMe) { - fVe.build(fMe); + fVe.buildFrom(fMe); init_fVe = true; } diff --git a/modules/vs/test/visual-feature/testFeature.cpp b/modules/vs/test/visual-feature/testFeature.cpp index f40891369b..c13ebe8bae 100644 --- a/modules/vs/test/visual-feature/testFeature.cpp +++ b/modules/vs/test/visual-feature/testFeature.cpp @@ -70,7 +70,7 @@ int main() // Creation of the current feature s vpFeatureThetaU s(vpFeatureThetaU::cdRc); - s.build(tu_cdRc); + s.buildFrom(tu_cdRc); s.print(); task.addFeature(s); // Add current ThetaU feature diff --git a/tutorial/computer-vision/tutorial-homography-from-points.cpp b/tutorial/computer-vision/tutorial-homography-from-points.cpp index 7ae965dff1..bf0a100280 100644 --- a/tutorial/computer-vision/tutorial-homography-from-points.cpp +++ b/tutorial/computer-vision/tutorial-homography-from-points.cpp @@ -59,7 +59,7 @@ int main() std::cout << "\nEstimated displacement:" << std::endl; std::cout << " atb: " << atb.t() << std::endl; vpThetaUVector atub; - atub.build(aRb); + atub.buildFrom(aRb); std::cout << " athetaub: "; for (unsigned int i = 0; i < 3; i++) std::cout << vpMath::deg(atub[i]) << " "; diff --git a/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp b/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp index 6c22bae85d..146f625986 100644 --- a/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp +++ b/tutorial/computer-vision/tutorial-pose-from-planar-object.cpp @@ -374,7 +374,7 @@ int main(int, char *argv[]) // Ask roi for plane estimation //! [Roi_Plane_Estimation] vpPolygon roi_color_img {}; - roi_color_img.build(getRoiFromUser(color_img), true); + roi_color_img.buildFrom(getRoiFromUser(color_img), true); std::vector roi_corners_depth_img {}; std::transform( diff --git a/tutorial/image/tutorial-draw-frame.cpp b/tutorial/image/tutorial-draw-frame.cpp index f5279f87ea..08f9acd619 100644 --- a/tutorial/image/tutorial-draw-frame.cpp +++ b/tutorial/image/tutorial-draw-frame.cpp @@ -44,7 +44,7 @@ int main() tOffset++; r[idAxis] = vpMath::rad(theta); vpHomogeneousMatrix cMo; - cMo.build(t, vpRotationMatrix(r)); + cMo.buildFrom(t, vpRotationMatrix(r)); std::stringstream ss_name; ss_name << "cMo_"; ss_name << static_cast(theta); diff --git a/tutorial/kalman/tutorial-ukf.cpp b/tutorial/kalman/tutorial-ukf.cpp index 318c53fd83..329b8732ad 100644 --- a/tutorial/kalman/tutorial-ukf.cpp +++ b/tutorial/kalman/tutorial-ukf.cpp @@ -157,7 +157,7 @@ class vpMarkersMeasurements vpColVector meas(2*nbMarkers); vpHomogeneousMatrix wMo; vpTranslationVector wTo(x[0], x[1], x[2]); - wMo.build(wTo, m_wRo); + wMo.buildFrom(wTo, m_wRo); for (unsigned int i = 0; i < nbMarkers; ++i) { vpColVector cX = m_cMw * wMo * m_markers[i]; double u = 0., v = 0.; @@ -183,7 +183,7 @@ class vpMarkersMeasurements vpColVector meas(2*nbMarkers); vpHomogeneousMatrix wMo; vpTranslationVector wTo(wX[0], wX[1], wX[2]); - wMo.build(wTo, m_wRo); + wMo.buildFrom(wTo, m_wRo); for (unsigned int i = 0; i < nbMarkers; ++i) { vpColVector cX = m_cMw * wMo * m_markers[i]; double u = 0., v = 0.; diff --git a/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-pf.cpp b/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-pf.cpp index 4c48f65328..3afc244d2e 100644 --- a/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-pf.cpp +++ b/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-pf.cpp @@ -118,8 +118,8 @@ void display(const vpColVector &coeffs, const vpImage &I, const vpColor &colo unsigned int width = I.getWidth(); vpTutoParabolaModel model(coeffs, I.getHeight(), I.getWidth()); for (unsigned int u = 0; u < width; ++u) { - float v = model.eval(u); - vpDisplay::displayPoint(I, v, u, color, 1); + double v = model.eval(u); + vpDisplay::displayPoint(I, static_cast(v), static_cast(u), color, 1); vpDisplay::displayText(I, vertPosLegend, horPosLegend, "Particle Filter model", color); } #else diff --git a/tutorial/particle-filter/tutorial-pf.cpp b/tutorial/particle-filter/tutorial-pf.cpp index 7a22de0f1f..e738730005 100644 --- a/tutorial/particle-filter/tutorial-pf.cpp +++ b/tutorial/particle-filter/tutorial-pf.cpp @@ -238,7 +238,7 @@ class vpMarkersMeasurements vpColVector meas(2*nbMarkers); vpHomogeneousMatrix wMo; vpTranslationVector wTo(x[0], x[1], x[2]); - wMo.build(wTo, m_wRo); + wMo.buildFrom(wTo, m_wRo); for (unsigned int i = 0; i < nbMarkers; ++i) { vpColVector cX = m_cMw * wMo * m_markers[i]; double u = 0., v = 0.; @@ -264,7 +264,7 @@ class vpMarkersMeasurements vpColVector meas(2*nbMarkers); vpHomogeneousMatrix wMo; vpTranslationVector wTo(wX[0], wX[1], wX[2]); - wMo.build(wTo, m_wRo); + wMo.buildFrom(wTo, m_wRo); for (unsigned int i = 0; i < nbMarkers; ++i) { vpColVector cX = m_cMw * wMo * m_markers[i]; double u = 0., v = 0.; @@ -315,7 +315,7 @@ class vpMarkersMeasurements double likelihood = 0.; vpHomogeneousMatrix wMo; vpTranslationVector wTo(x[0], x[1], x[2]); - wMo.build(wTo, m_wRo); + wMo.buildFrom(wTo, m_wRo); const unsigned int sizePt2D = 2; const unsigned int idX = 0, idY = 1, idZ = 2; double sumError = 0.; diff --git a/tutorial/robot/flir-ptu/tutorial-flir-ptu-ibvs.cpp b/tutorial/robot/flir-ptu/tutorial-flir-ptu-ibvs.cpp index 13e89d0015..a4de8585f5 100644 --- a/tutorial/robot/flir-ptu/tutorial-flir-ptu-ibvs.cpp +++ b/tutorial/robot/flir-ptu/tutorial-flir-ptu-ibvs.cpp @@ -180,7 +180,7 @@ int main(int argc, char **argv) if (!opt_extrinsic.empty()) { vpPoseVector ePc; ePc.loadYAML(opt_extrinsic, ePc); - eMc.build(ePc); + eMc.buildFrom(ePc); } std::cout << "Considered extrinsic transformation eMc:\n" << eMc << std::endl; diff --git a/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-2D-half-vs.cpp b/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-2D-half-vs.cpp index 11c738f0d3..3073a86690 100644 --- a/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-2D-half-vs.cpp +++ b/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-2D-half-vs.cpp @@ -181,7 +181,7 @@ int main(int argc, const char **argv) vpFeatureBuilder::create(s_x, cam, cog); // Create the desired x* visual feature - s_xd.build(0, 0, Z_d); + s_xd.buildFrom(0, 0, Z_d); // Add the point feature task.addFeature(s_x, s_xd, vpFeaturePoint::selectX()); @@ -190,8 +190,8 @@ int main(int argc, const char **argv) vpFeatureDepth s_Z, s_Z_d; std::cout << "Z " << Z << std::endl; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, 0); // log(Z/Z*) = 0 that's why the last parameter is 0 - s_Z_d.build(0, 0, Z_d, 0); // The value of s* is 0 with Z=1 meter + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, 0); // log(Z/Z*) = 0 that's why the last parameter is 0 + s_Z_d.buildFrom(0, 0, Z_d, 0); // The value of s* is 0 with Z=1 meter // Add the feature task.addFeature(s_Z, s_Z_d); @@ -251,7 +251,7 @@ int main(int argc, const char **argv) s_x.set_Z(Z); // Update log(Z/Z*) feature - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Z_d)); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Z_d)); std::cout << "cog: " << detector.getCog(0) << " Z: " << Z << std::endl; @@ -321,7 +321,7 @@ int main(int argc, const char **argv) std::cerr << "Catch an exception: " << e.getMessage() << std::endl; if (!serial_off) { serial->write("LED_RING=1,10,0,0\n"); // Switch on led 1 to red -} + } } return EXIT_SUCCESS; diff --git a/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-pbvs.cpp b/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-pbvs.cpp index 9ed3e50003..12cab7c7f8 100644 --- a/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-pbvs.cpp +++ b/tutorial/robot/mbot/raspberry/visp/mbot-apriltag-pbvs.cpp @@ -171,12 +171,12 @@ int main(int argc, const char **argv) // Create X_3D visual features vpFeaturePoint3D s_XZ, s_XZ_d; - s_XZ.build(0, 0, Z_d); - s_XZ_d.build(0, 0, Z_d); + s_XZ.buildFrom(0, 0, Z_d); + s_XZ_d.buildFrom(0, 0, Z_d); // Create Point 3D X, Z coordinates visual features - s_XZ.build(X, Y, Z); - s_XZ_d.build(0, 0, Z_d); // The value of s* is X=Y=0 and Z=Z_d meter + s_XZ.buildFrom(X, Y, Z); + s_XZ_d.buildFrom(0, 0, Z_d); // The value of s* is X=Y=0 and Z=Z_d meter // Add the features task.addFeature(s_XZ, s_XZ_d, vpFeaturePoint3D::selectX() | vpFeaturePoint3D::selectZ()); @@ -287,7 +287,7 @@ int main(int argc, const char **argv) std::cerr << "Catch an exception: " << e.getMessage() << std::endl; if (!serial_off) { serial->write("LED_RING=1,10,0,0\n"); // Switch on led 1 to red -} + } } return EXIT_SUCCESS; diff --git a/tutorial/robot/pioneer/tutorial-simu-pioneer-continuous-gain-adaptive.cpp b/tutorial/robot/pioneer/tutorial-simu-pioneer-continuous-gain-adaptive.cpp index a7205d8771..7e7544034a 100644 --- a/tutorial/robot/pioneer/tutorial-simu-pioneer-continuous-gain-adaptive.cpp +++ b/tutorial/robot/pioneer/tutorial-simu-pioneer-continuous-gain-adaptive.cpp @@ -68,14 +68,14 @@ int main() vpFeaturePoint s_x, s_xd; vpFeatureBuilder::create(s_x, point); - s_xd.build(0, 0, cdMo[2][3]); + s_xd.buildFrom(0, 0, cdMo[2][3]); task.addFeature(s_x, s_xd, vpFeaturePoint::selectX()); vpFeatureDepth s_Z, s_Zd; double Z = point.get_Z(); double Zd = cdMo[2][3]; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); - s_Zd.build(0, 0, Zd, 0); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Zd.buildFrom(0, 0, Zd, 0); task.addFeature(s_Z, s_Zd); #ifdef VISP_HAVE_DISPLAY @@ -106,7 +106,7 @@ int main() vpFeatureBuilder::create(s_x, point); Z = point.get_Z(); - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); robot.get_cVe(cVe); task.set_cVe(cVe); @@ -142,8 +142,8 @@ int main() // Kill the servo task task.print(); - } + } catch (const vpException &e) { std::cout << "Catch an exception: " << e << std::endl; } - } +} diff --git a/tutorial/robot/pioneer/tutorial-simu-pioneer-continuous-gain-constant.cpp b/tutorial/robot/pioneer/tutorial-simu-pioneer-continuous-gain-constant.cpp index 50bbc724be..ee0c2ad3eb 100644 --- a/tutorial/robot/pioneer/tutorial-simu-pioneer-continuous-gain-constant.cpp +++ b/tutorial/robot/pioneer/tutorial-simu-pioneer-continuous-gain-constant.cpp @@ -68,14 +68,14 @@ int main() vpFeaturePoint s_x, s_xd; vpFeatureBuilder::create(s_x, point); - s_xd.build(0, 0, cdMo[2][3]); + s_xd.buildFrom(0, 0, cdMo[2][3]); task.addFeature(s_x, s_xd, vpFeaturePoint::selectX()); vpFeatureDepth s_Z, s_Zd; double Z = point.get_Z(); double Zd = cdMo[2][3]; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); - s_Zd.build(0, 0, Zd, 0); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Zd.buildFrom(0, 0, Zd, 0); task.addFeature(s_Z, s_Zd); #ifdef VISP_HAVE_DISPLAY @@ -106,7 +106,7 @@ int main() vpFeatureBuilder::create(s_x, point); Z = point.get_Z(); - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); robot.get_cVe(cVe); task.set_cVe(cVe); diff --git a/tutorial/robot/pioneer/tutorial-simu-pioneer-pan.cpp b/tutorial/robot/pioneer/tutorial-simu-pioneer-pan.cpp index 3812dc1b47..6c3d0cbd96 100644 --- a/tutorial/robot/pioneer/tutorial-simu-pioneer-pan.cpp +++ b/tutorial/robot/pioneer/tutorial-simu-pioneer-pan.cpp @@ -83,7 +83,7 @@ int main() vpFeatureBuilder::create(s_x, point); // Create the desired x* visual feature - s_xd.build(0, 0, cdMo[2][3]); + s_xd.buildFrom(0, 0, cdMo[2][3]); // Add the feature task.addFeature(s_x, s_xd, vpFeaturePoint::selectX()); @@ -94,8 +94,8 @@ int main() double Z = point.get_Z(); // Desired depth Z* of the target. double Zd = cdMo[2][3]; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); - s_Zd.build(0, 0, Zd, + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Zd.buildFrom(0, 0, Zd, 0); // log(Z/Z*) = 0 that's why the last parameter is 0 // Add the feature @@ -133,7 +133,7 @@ int main() // Update log(Z/Z*) feature. Since the depth Z change, we need to update // the intection matrix Z = point.get_Z(); - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); robot.get_cVe(cVe); task.set_cVe(cVe); diff --git a/tutorial/robot/pioneer/tutorial-simu-pioneer.cpp b/tutorial/robot/pioneer/tutorial-simu-pioneer.cpp index 4160f3ed05..76d2e02131 100644 --- a/tutorial/robot/pioneer/tutorial-simu-pioneer.cpp +++ b/tutorial/robot/pioneer/tutorial-simu-pioneer.cpp @@ -68,14 +68,14 @@ int main() vpFeaturePoint s_x, s_xd; vpFeatureBuilder::create(s_x, point); - s_xd.build(0, 0, cdMo[2][3]); + s_xd.buildFrom(0, 0, cdMo[2][3]); task.addFeature(s_x, s_xd, vpFeaturePoint::selectX()); vpFeatureDepth s_Z, s_Zd; double Z = point.get_Z(); double Zd = cdMo[2][3]; - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); - s_Zd.build(0, 0, Zd, 0); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Zd.buildFrom(0, 0, Zd, 0); task.addFeature(s_Z, s_Zd); #ifdef VISP_HAVE_DISPLAY @@ -106,7 +106,7 @@ int main() vpFeatureBuilder::create(s_x, point); Z = point.get_Z(); - s_Z.build(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); + s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd)); robot.get_cVe(cVe); task.set_cVe(cVe); diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp index 6b69fc67d3..6977a756b5 100644 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-read.cpp @@ -1,3 +1,4 @@ +//! \example tutorial-mb-generic-tracker-read.cpp #include #include #include diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp index 5df4683ebb..578d529d17 100644 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-save.cpp @@ -1,10 +1,10 @@ +//! \example tutorial-mb-generic-tracker-save.cpp #include #include #include #include #include - #if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME;